diff --git a/.circleci/config.yml b/.circleci/config.yml
new file mode 100644
index 0000000000..f6eff674de
--- /dev/null
+++ b/.circleci/config.yml
@@ -0,0 +1,28 @@
+version: 2.1
+
+orbs:
+ python: circleci/python@1.4.0
+
+jobs:
+ build_doc:
+ docker:
+ - image: cimg/python:3.13
+ steps:
+ - checkout
+ - run:
+ name: doc_build
+ command: |
+ python --version
+ python -m venv venv
+ . venv/bin/activate
+ pip install -r requirements/requirements.txt
+ pip install -r docs/doc_requirements.txt
+ cd docs;make html
+ - store_artifacts:
+ path: docs/_build/html/
+ destination: html
+
+workflows:
+ main:
+ jobs:
+ - build_doc
diff --git a/.github/FUNDING.yml b/.github/FUNDING.yml
index 80f4984c3f..0d943696cc 100644
--- a/.github/FUNDING.yml
+++ b/.github/FUNDING.yml
@@ -1,3 +1,4 @@
# These are supported funding model platforms
+github: AtsushiSakai
patreon: myenigma
-custom: https://www.paypal.me/myenigmapay/
+custom: https://www.paypal.com/paypalme/myenigmapay/
diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md
new file mode 100644
index 0000000000..4f13bd074f
--- /dev/null
+++ b/.github/ISSUE_TEMPLATE/bug_report.md
@@ -0,0 +1,22 @@
+---
+name: Bug report
+about: Create a report to help us improve
+title: ''
+labels: ''
+assignees: ''
+
+---
+
+**Describe the bug**
+A clear and concise description of what the bug is.
+
+**Expected behavior**
+A clear and concise description of what you expected to happen.
+
+**Screenshots**
+If applicable, add screenshots to help explain your problem.
+
+**Desktop (please complete the following information):**
+ - Python version (This repo only supports Python 3.9.x or higher).
+ - Each library version
+ - OS version
diff --git a/.github/codeql/codeql-config.yml b/.github/codeql/codeql-config.yml
new file mode 100644
index 0000000000..4542231f10
--- /dev/null
+++ b/.github/codeql/codeql-config.yml
@@ -0,0 +1,6 @@
+name: "Extended CodeQL Config"
+
+# This file adds additional queries to the default configuration to make it equivalent to what LGTM checks.
+queries:
+ - name: Security and quality queries
+ uses: security-and-quality
diff --git a/.github/dependabot.yml b/.github/dependabot.yml
new file mode 100644
index 0000000000..6ffedf6f3b
--- /dev/null
+++ b/.github/dependabot.yml
@@ -0,0 +1,13 @@
+version: 2
+updates:
+- package-ecosystem: pip
+ directory: "/requirements"
+ schedule:
+ interval: weekly
+ time: "20:00"
+ open-pull-requests-limit: 10
+
+- package-ecosystem: github-actions
+ directory: "/"
+ schedule:
+ interval: weekly
diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md
new file mode 100644
index 0000000000..c0d9f7eab2
--- /dev/null
+++ b/.github/pull_request_template.md
@@ -0,0 +1,24 @@
+
+
+#### Reference issue
+
+
+#### What does this implement/fix?
+
+
+#### Additional information
+
+
+#### CheckList
+- [ ] Did you add an unittest for your new example or defect fix?
+- [ ] Did you add documents for your new example?
+- [ ] All CIs are green? (You can check it after submitting)
diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml
new file mode 100644
index 0000000000..152a3b0682
--- /dev/null
+++ b/.github/workflows/Linux_CI.yml
@@ -0,0 +1,37 @@
+name: Linux_CI
+
+on:
+ push:
+ branches:
+ - master
+ pull_request:
+
+jobs:
+ build:
+
+ runs-on: ubuntu-latest
+ strategy:
+ matrix:
+ python-version: [ '3.13' ]
+
+ name: Python ${{ matrix.python-version }} CI
+
+ steps:
+ - uses: actions/checkout@v5
+ - run: git fetch --prune --unshallow
+
+ - name: Setup python
+ uses: actions/setup-python@v6
+ with:
+ python-version: ${{ matrix.python-version }}
+ - name: Install dependencies
+ run: |
+ python --version
+ python -m pip install --upgrade pip
+ python -m pip install -r requirements/requirements.txt
+ - name: do all unit tests
+ run: bash runtests.sh
+
+
+
+
diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml
new file mode 100644
index 0000000000..ab04dc01dc
--- /dev/null
+++ b/.github/workflows/MacOS_CI.yml
@@ -0,0 +1,39 @@
+# This is a basic workflow to help you get started with Actions
+
+name: MacOS_CI
+
+# Controls when the action will run. Triggers the workflow on push or pull request
+# events but only for the master branch
+on:
+ push:
+ branches:
+ - master
+ pull_request:
+
+
+jobs:
+ build:
+ runs-on: macos-latest
+ strategy:
+ matrix:
+ python-version: [ '3.13' ]
+ name: Python ${{ matrix.python-version }} CI
+ steps:
+ - uses: actions/checkout@v5
+ - run: git fetch --prune --unshallow
+
+ - name: Update bash
+ run: brew install bash
+
+ - name: Setup python
+ uses: actions/setup-python@v6
+ with:
+ python-version: ${{ matrix.python-version }}
+
+ - name: Install dependencies
+ run: |
+ python --version
+ python -m pip install --upgrade pip
+ pip install -r requirements/requirements.txt
+ - name: do all unit tests
+ run: bash runtests.sh
diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml
new file mode 100644
index 0000000000..a4385e595b
--- /dev/null
+++ b/.github/workflows/Windows_CI.yml
@@ -0,0 +1,36 @@
+# This is a basic workflow to help you get started with Actions
+
+name: Windows_CI
+
+# Controls when the action will run. Triggers the workflow on push or pull request
+# events but only for the master branch
+on:
+ push:
+ branches:
+ - master
+ pull_request:
+
+
+jobs:
+ build:
+ runs-on: windows-latest
+ strategy:
+ matrix:
+ python-version: [ '3.13' ]
+ name: Python ${{ matrix.python-version }} CI
+ steps:
+ - uses: actions/checkout@v5
+ - run: git fetch --prune --unshallow
+
+ - name: Setup python
+ uses: actions/setup-python@v6
+ with:
+ python-version: ${{ matrix.python-version }}
+
+ - name: Install dependencies
+ run: |
+ python --version
+ python -m pip install --upgrade pip
+ pip install -r requirements/requirements.txt
+ - name: do all unit tests
+ run: bash runtests.sh
diff --git a/.github/workflows/circleci-artifacts-redirector.yml b/.github/workflows/circleci-artifacts-redirector.yml
new file mode 100644
index 0000000000..0e64bab96c
--- /dev/null
+++ b/.github/workflows/circleci-artifacts-redirector.yml
@@ -0,0 +1,14 @@
+name: circleci-artifacts-redirector-action
+on: [status]
+jobs:
+ circleci_artifacts_redirector_job:
+ runs-on: ubuntu-latest
+ name: Run CircleCI artifacts redirector!!
+ steps:
+ - name: run-circleci-artifacts-redirector
+ uses: larsoner/circleci-artifacts-redirector-action@v1.3.1
+ with:
+ repo-token: ${{ secrets.GITHUB_TOKEN }}
+ api-token: ${{ secrets.CIRCLECI_TOKEN }}
+ artifact-path: 0/html/index.html
+ circleci-jobs: build_doc
diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml
new file mode 100644
index 0000000000..0ed1d7e90d
--- /dev/null
+++ b/.github/workflows/codeql.yml
@@ -0,0 +1,51 @@
+name: "Code scanning - action"
+
+on:
+ push:
+ branches:
+ - master
+ pull_request:
+ schedule:
+ - cron: '0 19 * * 0'
+
+jobs:
+ CodeQL-Build:
+
+ # CodeQL runs on ubuntu-latest and windows-latest
+ runs-on: ubuntu-latest
+
+ steps:
+ - name: Checkout repository
+ uses: actions/checkout@v5
+ with:
+ # We must fetch at least the immediate parents so that if this is
+ # a pull request then we can checkout the head.
+ fetch-depth: 2
+
+ # Initializes the CodeQL tools for scanning.
+ - name: Initialize CodeQL
+ uses: github/codeql-action/init@v3
+ with:
+ config-file: ./.github/codeql/codeql-config.yml
+ # Override language selection by uncommenting this and choosing your languages
+ # with:
+ # languages: go, javascript, csharp, python, cpp, java
+
+ # Autobuild attempts to build any compiled languages (C/C++, C#, or Java).
+ # If this step fails, then you should remove it and run the build manually (see below)
+ - name: Autobuild
+ uses: github/codeql-action/autobuild@v3
+
+ # ℹ️ Command-line programs to run using the OS shell.
+ # 📚 https://git.io/JvXDl
+
+ # ✏️ If the Autobuild fails above, remove it and uncomment the following three lines
+ # and modify them (or add more) to build your code if your project
+ # uses a compiled language
+
+ #- run: |
+ # make bootstrap
+ # make release
+
+ - name: Perform CodeQL Analysis
+ uses: github/codeql-action/analyze@v3
diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml
new file mode 100644
index 0000000000..84165b9cd2
--- /dev/null
+++ b/.github/workflows/gh-pages.yml
@@ -0,0 +1,30 @@
+name: GitHub Pages site update
+on:
+ push:
+ branches:
+ - master
+jobs:
+ build:
+ runs-on: ubuntu-latest
+ environment:
+ name: github-pages
+ url: ${{ steps.deployment.outputs.page_url }}
+ permissions:
+ id-token: write
+ pages: write
+ steps:
+ - name: Setup python
+ uses: actions/setup-python@v6
+ - name: Checkout
+ uses: actions/checkout@master
+ with:
+ fetch-depth: 0 # otherwise, you will fail to push refs to dest repo
+ - name: Install dependencies
+ run: |
+ python --version
+ python -m pip install --upgrade pip
+ python -m pip install -r requirements/requirements.txt
+ - name: Build and Deploy
+ uses: sphinx-notes/pages@v3
+ with:
+ requirements_path: ./docs/doc_requirements.txt
diff --git a/.gitignore b/.gitignore
index 62e48c6762..c971b8f9c5 100644
--- a/.gitignore
+++ b/.gitignore
@@ -68,3 +68,6 @@ target/
#Ipython Notebook
.ipynb_checkpoints
+
+matplotrecorder/*
+.vscode/settings.json
diff --git a/.lgtm.yml b/.lgtm.yml
deleted file mode 100644
index b06edf3510..0000000000
--- a/.lgtm.yml
+++ /dev/null
@@ -1,4 +0,0 @@
-extraction:
- python:
- python_setup:
- version: 3
diff --git a/.travis.yml b/.travis.yml
deleted file mode 100644
index eff3df24fa..0000000000
--- a/.travis.yml
+++ /dev/null
@@ -1,36 +0,0 @@
-language: python
-
-matrix:
- include:
- - os: linux
-
-python:
- - 3.6
-
-before_install:
- - sudo apt-get update
- - wget https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh -O miniconda.sh
- - chmod +x miniconda.sh
- - bash miniconda.sh -b -p $HOME/miniconda
- - export PATH="$HOME/miniconda/bin:$PATH"
- - hash -r
- - conda config --set always_yes yes --set changeps1 no
- - conda update -q conda
- # Useful for debugging any issues with conda
- - conda info -a
- - conda install python==3.6.8
-
-install:
- - conda install numpy==1.15
- - conda install scipy
- - conda install matplotlib
- - conda install pandas
- - pip install cvxpy
- - conda install coveralls
-
-script:
- - python --version
- - ./runtests.sh
-
-after_success:
- - coveralls
diff --git a/PathPlanning/ClosedLoopRRTStar/__init__.py b/AerialNavigation/__init__.py
similarity index 100%
rename from PathPlanning/ClosedLoopRRTStar/__init__.py
rename to AerialNavigation/__init__.py
diff --git a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py
index 9b38677cbe..c379e5eda0 100644
--- a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py
+++ b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py
@@ -8,7 +8,6 @@
import numpy as np
import matplotlib.pyplot as plt
-
class Quadrotor():
def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animation=True):
self.p1 = np.array([size / 2, 0, 0, 1]).T
@@ -24,6 +23,10 @@ def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animat
if self.show_animation:
plt.ion()
fig = plt.figure()
+ # for stopping simulation with the esc key.
+ fig.canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
self.ax = fig.add_subplot(111, projection='3d')
self.update_pose(x, y, z, roll, pitch, yaw)
@@ -53,7 +56,7 @@ def transformation_matrix(self):
[[cos(yaw) * cos(pitch), -sin(yaw) * cos(roll) + cos(yaw) * sin(pitch) * sin(roll), sin(yaw) * sin(roll) + cos(yaw) * sin(pitch) * cos(roll), x],
[sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch)
* sin(roll), -cos(yaw) * sin(roll) + sin(yaw) * sin(pitch) * cos(roll), y],
- [-sin(pitch), cos(pitch) * sin(roll), cos(pitch) * cos(yaw), z]
+ [-sin(pitch), cos(pitch) * sin(roll), cos(pitch) * cos(roll), z]
])
def plot(self): # pragma: no cover
@@ -81,4 +84,4 @@ def plot(self): # pragma: no cover
plt.ylim(-5, 5)
self.ax.set_zlim(0, 10)
- plt.pause(0.001)
\ No newline at end of file
+ plt.pause(0.001)
diff --git a/AerialNavigation/drone_3d_trajectory_following/__init__.py b/AerialNavigation/drone_3d_trajectory_following/__init__.py
new file mode 100644
index 0000000000..2194d4c303
--- /dev/null
+++ b/AerialNavigation/drone_3d_trajectory_following/__init__.py
@@ -0,0 +1,3 @@
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent))
diff --git a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py
index 438494a410..029e82be62 100644
--- a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py
+++ b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py
@@ -8,7 +8,6 @@
import numpy as np
from Quadrotor import Quadrotor
from TrajectoryGenerator import TrajectoryGenerator
-from mpl_toolkits.mplot3d import Axes3D
show_animation = True
@@ -99,7 +98,7 @@ def quad_sim(x_c, y_c, z_c):
R = rotation_matrix(roll, pitch, yaw)
acc = (np.matmul(R, np.array(
- [0, 0, thrust]).T) - np.array([0, 0, m * g]).T) / m
+ [0, 0, thrust.item()]).T) - np.array([0, 0, m * g]).T) / m
x_acc = acc[0]
y_acc = acc[1]
z_acc = acc[2]
@@ -128,7 +127,7 @@ def calculate_position(c, t):
Calculates a position given a set of quintic coefficients and a time.
Args
- c: List of coefficients generated by a quintic polynomial
+ c: List of coefficients generated by a quintic polynomial
trajectory generator.
t: Time at which to calculate the position
@@ -143,7 +142,7 @@ def calculate_velocity(c, t):
Calculates a velocity given a set of quintic coefficients and a time.
Args
- c: List of coefficients generated by a quintic polynomial
+ c: List of coefficients generated by a quintic polynomial
trajectory generator.
t: Time at which to calculate the velocity
@@ -158,7 +157,7 @@ def calculate_acceleration(c, t):
Calculates an acceleration given a set of quintic coefficients and a time.
Args
- c: List of coefficients generated by a quintic polynomial
+ c: List of coefficients generated by a quintic polynomial
trajectory generator.
t: Time at which to calculate the acceleration
@@ -168,7 +167,7 @@ def calculate_acceleration(c, t):
return 20 * c[0] * t**3 + 12 * c[1] * t**2 + 6 * c[2] * t + 2 * c[3]
-def rotation_matrix(roll, pitch, yaw):
+def rotation_matrix(roll_array, pitch_array, yaw):
"""
Calculates the ZYX rotation matrix.
@@ -180,6 +179,8 @@ def rotation_matrix(roll, pitch, yaw):
Returns
3x3 rotation matrix as NumPy array
"""
+ roll = roll_array[0]
+ pitch = pitch_array[0]
return np.array(
[[cos(yaw) * cos(pitch), -sin(yaw) * cos(roll) + cos(yaw) * sin(pitch) * sin(roll), sin(yaw) * sin(roll) + cos(yaw) * sin(pitch) * cos(roll)],
[sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch) *
@@ -190,7 +191,7 @@ def rotation_matrix(roll, pitch, yaw):
def main():
"""
- Calculates the x, y, z coefficients for the four segments
+ Calculates the x, y, z coefficients for the four segments
of the trajectory
"""
x_coeffs = [[], [], [], []]
@@ -209,4 +210,4 @@ def main():
if __name__ == "__main__":
- main()
\ No newline at end of file
+ main()
diff --git a/AerialNavigation/rocket_powered_landing/figure.png b/AerialNavigation/rocket_powered_landing/figure.png
deleted file mode 100644
index 0be109ed2b..0000000000
Binary files a/AerialNavigation/rocket_powered_landing/figure.png and /dev/null differ
diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb
deleted file mode 100644
index 308512bfd7..0000000000
--- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb
+++ /dev/null
@@ -1,482 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Simulation"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 16,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/html": [
- "\n",
- "\n"
- ],
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"figure.png\",width=600)\n",
- "from IPython.display import display, HTML\n",
- "\n",
- "display(HTML(data=\"\"\"\n",
- "\n",
- "\"\"\"))"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- ""
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Equation generation"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [],
- "source": [
- "import sympy as sp\n",
- "import numpy as np\n",
- "from IPython.display import display\n",
- "sp.init_printing(use_latex='mathjax')"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 6,
- "metadata": {},
- "outputs": [],
- "source": [
- "# parameters\n",
- "# Angular moment of inertia\n",
- "J_B = 1e-2 * np.diag([1., 1., 1.])\n",
- "\n",
- "# Gravity\n",
- "g_I = np.array((-1, 0., 0.))\n",
- "\n",
- "# Fuel consumption\n",
- "alpha_m = 0.01\n",
- "\n",
- "# Vector from thrust point to CoM\n",
- "r_T_B = np.array([-1e-2, 0., 0.])\n",
- "\n",
- "\n",
- "def dir_cosine(q):\n",
- " return np.matrix([\n",
- " [1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2] +\n",
- " q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])],\n",
- " [2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2 *\n",
- " (q[1] ** 2 + q[3] ** 2), 2 * (q[2] * q[3] + q[0] * q[1])],\n",
- " [2 * (q[1] * q[3] + q[0] * q[2]), 2 * (q[2] * q[3] -\n",
- " q[0] * q[1]), 1 - 2 * (q[1] ** 2 + q[2] ** 2)]\n",
- " ])\n",
- "\n",
- "def omega(w):\n",
- " return np.matrix([\n",
- " [0, -w[0], -w[1], -w[2]],\n",
- " [w[0], 0, w[2], -w[1]],\n",
- " [w[1], -w[2], 0, w[0]],\n",
- " [w[2], w[1], -w[0], 0],\n",
- " ])\n",
- "\n",
- "def skew(v):\n",
- " return np.matrix([\n",
- " [0, -v[2], v[1]],\n",
- " [v[2], 0, -v[0]],\n",
- " [-v[1], v[0], 0]\n",
- " ])\n",
- "\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 7,
- "metadata": {},
- "outputs": [],
- "source": [
- "f = sp.zeros(14, 1)\n",
- "\n",
- "x = sp.Matrix(sp.symbols(\n",
- " 'm rx ry rz vx vy vz q0 q1 q2 q3 wx wy wz', real=True))\n",
- "u = sp.Matrix(sp.symbols('ux uy uz', real=True))\n",
- "\n",
- "g_I = sp.Matrix(g_I)\n",
- "r_T_B = sp.Matrix(r_T_B)\n",
- "J_B = sp.Matrix(J_B)\n",
- "\n",
- "C_B_I = dir_cosine(x[7:11, 0])\n",
- "C_I_B = C_B_I.transpose()\n",
- "\n",
- "f[0, 0] = - alpha_m * u.norm()\n",
- "f[1:4, 0] = x[4:7, 0]\n",
- "f[4:7, 0] = 1 / x[0, 0] * C_I_B * u + g_I\n",
- "f[7:11, 0] = 1 / 2 * omega(x[11:14, 0]) * x[7: 11, 0]\n",
- "f[11:14, 0] = J_B ** -1 * \\\n",
- " (skew(r_T_B) * u - skew(x[11:14, 0]) * J_B * x[11:14, 0])\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 8,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/latex": [
- "$$\\left[\\begin{matrix}- 0.01 \\sqrt{ux^{2} + uy^{2} + uz^{2}}\\\\vx\\\\vy\\\\vz\\\\\\frac{- 1.0 m - ux \\left(2 q_{2}^{2} + 2 q_{3}^{2} - 1\\right) - 2 uy \\left(q_{0} q_{3} - q_{1} q_{2}\\right) + 2 uz \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m}\\\\\\frac{2 ux \\left(q_{0} q_{3} + q_{1} q_{2}\\right) - uy \\left(2 q_{1}^{2} + 2 q_{3}^{2} - 1\\right) - 2 uz \\left(q_{0} q_{1} - q_{2} q_{3}\\right)}{m}\\\\\\frac{- 2 ux \\left(q_{0} q_{2} - q_{1} q_{3}\\right) + 2 uy \\left(q_{0} q_{1} + q_{2} q_{3}\\right) - uz \\left(2 q_{1}^{2} + 2 q_{2}^{2} - 1\\right)}{m}\\\\- 0.5 q_{1} wx - 0.5 q_{2} wy - 0.5 q_{3} wz\\\\0.5 q_{0} wx + 0.5 q_{2} wz - 0.5 q_{3} wy\\\\0.5 q_{0} wy - 0.5 q_{1} wz + 0.5 q_{3} wx\\\\0.5 q_{0} wz + 0.5 q_{1} wy - 0.5 q_{2} wx\\\\0\\\\1.0 uz\\\\- 1.0 uy\\end{matrix}\\right]$$"
- ],
- "text/plain": [
- "⎡ _________________ \n",
- "⎢ ╱ 2 2 2 \n",
- "⎢ -0.01⋅╲╱ ux + uy + uz \n",
- "⎢ \n",
- "⎢ vx \n",
- "⎢ \n",
- "⎢ vy \n",
- "⎢ \n",
- "⎢ vz \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢-1.0⋅m - ux⋅⎝2⋅q₂ + 2⋅q₃ - 1⎠ - 2⋅uy⋅(q₀⋅q₃ - q₁⋅q₂) + 2⋅uz⋅(q₀⋅q₂ + q₁⋅q₃)\n",
- "⎢─────────────────────────────────────────────────────────────────────────────\n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢ 2⋅ux⋅(q₀⋅q₃ + q₁⋅q₂) - uy⋅⎝2⋅q₁ + 2⋅q₃ - 1⎠ - 2⋅uz⋅(q₀⋅q₁ - q₂⋅q₃) \n",
- "⎢ ──────────────────────────────────────────────────────────────────── \n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢ -2⋅ux⋅(q₀⋅q₂ - q₁⋅q₃) + 2⋅uy⋅(q₀⋅q₁ + q₂⋅q₃) - uz⋅⎝2⋅q₁ + 2⋅q₂ - 1⎠ \n",
- "⎢ ───────────────────────────────────────────────────────────────────── \n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ -0.5⋅q₁⋅wx - 0.5⋅q₂⋅wy - 0.5⋅q₃⋅wz \n",
- "⎢ \n",
- "⎢ 0.5⋅q₀⋅wx + 0.5⋅q₂⋅wz - 0.5⋅q₃⋅wy \n",
- "⎢ \n",
- "⎢ 0.5⋅q₀⋅wy - 0.5⋅q₁⋅wz + 0.5⋅q₃⋅wx \n",
- "⎢ \n",
- "⎢ 0.5⋅q₀⋅wz + 0.5⋅q₁⋅wy - 0.5⋅q₂⋅wx \n",
- "⎢ \n",
- "⎢ 0 \n",
- "⎢ \n",
- "⎢ 1.0⋅uz \n",
- "⎢ \n",
- "⎣ -1.0⋅uy \n",
- "\n",
- "⎤\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎥\n",
- "⎦"
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "display(sp.simplify(f)) # f"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 12,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/latex": [
- "$$\\left[\\begin{array}{cccccccccccccc}0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\\\frac{ux \\left(2 q_{2}^{2} + 2 q_{3}^{2} - 1\\right) + 2 uy \\left(q_{0} q_{3} - q_{1} q_{2}\\right) - 2 uz \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(q_{2} uz - q_{3} uy\\right)}{m} & \\frac{2 \\left(q_{2} uy + q_{3} uz\\right)}{m} & \\frac{2 \\left(q_{0} uz + q_{1} uy - 2 q_{2} ux\\right)}{m} & \\frac{2 \\left(- q_{0} uy + q_{1} uz - 2 q_{3} ux\\right)}{m} & 0 & 0 & 0\\\\\\frac{- 2 ux \\left(q_{0} q_{3} + q_{1} q_{2}\\right) + uy \\left(2 q_{1}^{2} + 2 q_{3}^{2} - 1\\right) + 2 uz \\left(q_{0} q_{1} - q_{2} q_{3}\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(- q_{1} uz + q_{3} ux\\right)}{m} & \\frac{2 \\left(- q_{0} uz - 2 q_{1} uy + q_{2} ux\\right)}{m} & \\frac{2 \\left(q_{1} ux + q_{3} uz\\right)}{m} & \\frac{2 \\left(q_{0} ux + q_{2} uz - 2 q_{3} uy\\right)}{m} & 0 & 0 & 0\\\\\\frac{2 ux \\left(q_{0} q_{2} - q_{1} q_{3}\\right) - 2 uy \\left(q_{0} q_{1} + q_{2} q_{3}\\right) + uz \\left(2 q_{1}^{2} + 2 q_{2}^{2} - 1\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(q_{1} uy - q_{2} ux\\right)}{m} & \\frac{2 \\left(q_{0} uy - 2 q_{1} uz + q_{3} ux\\right)}{m} & \\frac{2 \\left(- q_{0} ux - 2 q_{2} uz + q_{3} uy\\right)}{m} & \\frac{2 \\left(q_{1} ux + q_{2} uy\\right)}{m} & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & - 0.5 wx & - 0.5 wy & - 0.5 wz & - 0.5 q_{1} & - 0.5 q_{2} & - 0.5 q_{3}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wx & 0 & 0.5 wz & - 0.5 wy & 0.5 q_{0} & - 0.5 q_{3} & 0.5 q_{2}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wy & - 0.5 wz & 0 & 0.5 wx & 0.5 q_{3} & 0.5 q_{0} & - 0.5 q_{1}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wz & 0.5 wy & - 0.5 wx & 0 & - 0.5 q_{2} & 0.5 q_{1} & 0.5 q_{0}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\end{array}\\right]$$"
- ],
- "text/plain": [
- "⎡ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢ux⋅⎝2⋅q₂ + 2⋅q₃ - 1⎠ + 2⋅uy⋅(q₀⋅q₃ - q₁⋅q₂) - 2⋅uz⋅(q₀⋅q₂ + q₁⋅q₃) \n",
- "⎢──────────────────────────────────────────────────────────────────── 0 0 \n",
- "⎢ 2 \n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢-2⋅ux⋅(q₀⋅q₃ + q₁⋅q₂) + uy⋅⎝2⋅q₁ + 2⋅q₃ - 1⎠ + 2⋅uz⋅(q₀⋅q₁ - q₂⋅q₃) \n",
- "⎢───────────────────────────────────────────────────────────────────── 0 0 \n",
- "⎢ 2 \n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ ⎛ 2 2 ⎞ \n",
- "⎢2⋅ux⋅(q₀⋅q₂ - q₁⋅q₃) - 2⋅uy⋅(q₀⋅q₁ + q₂⋅q₃) + uz⋅⎝2⋅q₁ + 2⋅q₂ - 1⎠ \n",
- "⎢──────────────────────────────────────────────────────────────────── 0 0 \n",
- "⎢ 2 \n",
- "⎢ m \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎢ 0 0 0 \n",
- "⎢ \n",
- "⎣ 0 0 0 \n",
- "\n",
- "0 0 0 0 0 0 0 \n",
- " \n",
- "0 1 0 0 0 0 0 \n",
- " \n",
- "0 0 1 0 0 0 0 \n",
- " \n",
- "0 0 0 1 0 0 0 \n",
- " \n",
- " \n",
- " 2⋅(q₂⋅uz - q₃⋅uy) 2⋅(q₂⋅uy + q₃⋅uz) 2⋅(q₀⋅uz + q₁⋅uy\n",
- "0 0 0 0 ───────────────── ───────────────── ────────────────\n",
- " m m m \n",
- " \n",
- " \n",
- " \n",
- " 2⋅(-q₁⋅uz + q₃⋅ux) 2⋅(-q₀⋅uz - 2⋅q₁⋅uy + q₂⋅ux) 2⋅(q₁⋅ux + \n",
- "0 0 0 0 ────────────────── ──────────────────────────── ───────────\n",
- " m m m \n",
- " \n",
- " \n",
- " \n",
- " 2⋅(q₁⋅uy - q₂⋅ux) 2⋅(q₀⋅uy - 2⋅q₁⋅uz + q₃⋅ux) 2⋅(-q₀⋅ux - 2⋅q₂\n",
- "0 0 0 0 ───────────────── ─────────────────────────── ────────────────\n",
- " m m m \n",
- " \n",
- " \n",
- "0 0 0 0 0 -0.5⋅wx -0.5⋅w\n",
- " \n",
- "0 0 0 0 0.5⋅wx 0 0.5⋅w\n",
- " \n",
- "0 0 0 0 0.5⋅wy -0.5⋅wz 0 \n",
- " \n",
- "0 0 0 0 0.5⋅wz 0.5⋅wy -0.5⋅w\n",
- " \n",
- "0 0 0 0 0 0 0 \n",
- " \n",
- "0 0 0 0 0 0 0 \n",
- " \n",
- "0 0 0 0 0 0 0 \n",
- "\n",
- " 0 0 0 0 ⎤\n",
- " ⎥\n",
- " 0 0 0 0 ⎥\n",
- " ⎥\n",
- " 0 0 0 0 ⎥\n",
- " ⎥\n",
- " 0 0 0 0 ⎥\n",
- " ⎥\n",
- " ⎥\n",
- " - 2⋅q₂⋅ux) 2⋅(-q₀⋅uy + q₁⋅uz - 2⋅q₃⋅ux) ⎥\n",
- "─────────── ──────────────────────────── 0 0 0 ⎥\n",
- " m ⎥\n",
- " ⎥\n",
- " ⎥\n",
- " ⎥\n",
- "q₃⋅uz) 2⋅(q₀⋅ux + q₂⋅uz - 2⋅q₃⋅uy) ⎥\n",
- "────── ─────────────────────────── 0 0 0 ⎥\n",
- " m ⎥\n",
- " ⎥\n",
- " ⎥\n",
- " ⎥\n",
- "⋅uz + q₃⋅uy) 2⋅(q₁⋅ux + q₂⋅uy) ⎥\n",
- "──────────── ───────────────── 0 0 0 ⎥\n",
- " m ⎥\n",
- " ⎥\n",
- " ⎥\n",
- "y -0.5⋅wz -0.5⋅q₁ -0.5⋅q₂ -0.5⋅q₃⎥\n",
- " ⎥\n",
- "z -0.5⋅wy 0.5⋅q₀ -0.5⋅q₃ 0.5⋅q₂ ⎥\n",
- " ⎥\n",
- " 0.5⋅wx 0.5⋅q₃ 0.5⋅q₀ -0.5⋅q₁⎥\n",
- " ⎥\n",
- "x 0 -0.5⋅q₂ 0.5⋅q₁ 0.5⋅q₀ ⎥\n",
- " ⎥\n",
- " 0 0 0 0 ⎥\n",
- " ⎥\n",
- " 0 0 0 0 ⎥\n",
- " ⎥\n",
- " 0 0 0 0 ⎦"
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "display(sp.simplify(f.jacobian(x)))# A "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 10,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/latex": [
- "$$\\left[\\begin{matrix}- \\frac{0.01 ux}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}} & - \\frac{0.01 uy}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}} & - \\frac{0.01 uz}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}}\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\\\frac{- 2 q_{2}^{2} - 2 q_{3}^{2} + 1}{m} & \\frac{2 \\left(- q_{0} q_{3} + q_{1} q_{2}\\right)}{m} & \\frac{2 \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m}\\\\\\frac{2 \\left(q_{0} q_{3} + q_{1} q_{2}\\right)}{m} & \\frac{- 2 q_{1}^{2} - 2 q_{3}^{2} + 1}{m} & \\frac{2 \\left(- q_{0} q_{1} + q_{2} q_{3}\\right)}{m}\\\\\\frac{2 \\left(- q_{0} q_{2} + q_{1} q_{3}\\right)}{m} & \\frac{2 \\left(q_{0} q_{1} + q_{2} q_{3}\\right)}{m} & \\frac{- 2 q_{1}^{2} - 2 q_{2}^{2} + 1}{m}\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 1.0\\\\0 & -1.0 & 0\\end{matrix}\\right]$$"
- ],
- "text/plain": [
- "⎡ -0.01⋅ux -0.01⋅uy -0.01⋅uz ⎤\n",
- "⎢──────────────────── ──────────────────── ────────────────────⎥\n",
- "⎢ _________________ _________________ _________________⎥\n",
- "⎢ ╱ 2 2 2 ╱ 2 2 2 ╱ 2 2 2 ⎥\n",
- "⎢╲╱ ux + uy + uz ╲╱ ux + uy + uz ╲╱ ux + uy + uz ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 2 2 ⎥\n",
- "⎢- 2⋅q₂ - 2⋅q₃ + 1 2⋅(-q₀⋅q₃ + q₁⋅q₂) 2⋅(q₀⋅q₂ + q₁⋅q₃) ⎥\n",
- "⎢─────────────────── ────────────────── ───────────────── ⎥\n",
- "⎢ m m m ⎥\n",
- "⎢ ⎥\n",
- "⎢ 2 2 ⎥\n",
- "⎢ 2⋅(q₀⋅q₃ + q₁⋅q₂) - 2⋅q₁ - 2⋅q₃ + 1 2⋅(-q₀⋅q₁ + q₂⋅q₃) ⎥\n",
- "⎢ ───────────────── ─────────────────── ────────────────── ⎥\n",
- "⎢ m m m ⎥\n",
- "⎢ ⎥\n",
- "⎢ 2 2 ⎥\n",
- "⎢ 2⋅(-q₀⋅q₂ + q₁⋅q₃) 2⋅(q₀⋅q₁ + q₂⋅q₃) - 2⋅q₁ - 2⋅q₂ + 1 ⎥\n",
- "⎢ ────────────────── ───────────────── ─────────────────── ⎥\n",
- "⎢ m m m ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 0 ⎥\n",
- "⎢ ⎥\n",
- "⎢ 0 0 1.0 ⎥\n",
- "⎢ ⎥\n",
- "⎣ 0 -1.0 0 ⎦"
- ]
- },
- "execution_count": 10,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "sp.simplify(f.jacobian(u)) # B"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Ref\n",
- "\n",
- "- Python implementation of 'Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time' paper\n",
- "by Michael Szmuk and Behçet Açıkmeşe.\n",
- "\n",
- "- inspired by EmbersArc/SuccessiveConvexificationFreeFinalTime: Implementation of \"Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time\" https://github.com/EmbersArc/SuccessiveConvexificationFreeFinalTime\n",
- "\n"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.8"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py
index 9f1e16fc1d..e8ba8fa220 100644
--- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py
+++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py
@@ -5,20 +5,19 @@
author: Sven Niederberger
Atsushi Sakai
-Ref:
+Reference:
- Python implementation of 'Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time' paper
by Michael Szmuk and Behcet Acıkmese.
- EmbersArc/SuccessiveConvexificationFreeFinalTime: Implementation of "Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time" https://github.com/EmbersArc/SuccessiveConvexificationFreeFinalTime
"""
-
+import warnings
from time import time
import numpy as np
from scipy.integrate import odeint
import cvxpy
import matplotlib.pyplot as plt
-from mpl_toolkits import mplot3d
# Trajectory points
K = 50
@@ -32,6 +31,7 @@
W_DELTA_SIGMA = 1e-1 # difference in flight time
W_NU = 1e5 # virtual control
+print(cvxpy.installed_solvers())
solver = 'ECOS'
verbose_solver = False
@@ -43,7 +43,7 @@ class Rocket_Model_6DoF:
A 6 degree of freedom rocket landing problem.
"""
- def __init__(self):
+ def __init__(self, rng):
"""
A large r_scale for a small scale problem will
ead to numerical problems as parameters become excessively small
@@ -92,7 +92,7 @@ def __init__(self):
# Vector from thrust point to CoM
self.r_T_B = np.array([-1e-2, 0., 0.])
- self.set_random_initial_state()
+ self.set_random_initial_state(rng)
self.x_init = np.concatenate(
((self.m_wet,), self.r_I_init, self.v_I_init, self.q_B_I_init, self.w_B_init))
@@ -102,29 +102,32 @@ def __init__(self):
self.r_scale = np.linalg.norm(self.r_I_init)
self.m_scale = self.m_wet
- def set_random_initial_state(self):
+ def set_random_initial_state(self, rng):
+ if rng is None:
+ rng = np.random.default_rng()
+
self.r_I_init = np.array((0., 0., 0.))
- self.r_I_init[0] = np.random.uniform(3, 4)
- self.r_I_init[1:3] = np.random.uniform(-2, 2, size=2)
+ self.r_I_init[0] = rng.uniform(3, 4)
+ self.r_I_init[1:3] = rng.uniform(-2, 2, size=2)
self.v_I_init = np.array((0., 0., 0.))
- self.v_I_init[0] = np.random.uniform(-1, -0.5)
- self.v_I_init[1:3] = np.random.uniform(
- -0.5, -0.2, size=2) * self.r_I_init[1:3]
+ self.v_I_init[0] = rng.uniform(-1, -0.5)
+ self.v_I_init[1:3] = rng.uniform(-0.5, -0.2,
+ size=2) * self.r_I_init[1:3]
self.q_B_I_init = self.euler_to_quat((0,
- np.random.uniform(-30, 30),
- np.random.uniform(-30, 30)))
+ rng.uniform(-30, 30),
+ rng.uniform(-30, 30)))
self.w_B_init = np.deg2rad((0,
- np.random.uniform(-20, 20),
- np.random.uniform(-20, 20)))
+ rng.uniform(-20, 20),
+ rng.uniform(-20, 20)))
def f_func(self, x, u):
- m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[
+ m, _, _, _, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[
2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13]
ux, uy, uz = u[0], u[1], u[2]
- return np.matrix([
+ return np.array([
[-0.01 * np.sqrt(ux**2 + uy**2 + uz**2)],
[vx],
[vy],
@@ -145,11 +148,11 @@ def f_func(self, x, u):
])
def A_func(self, x, u):
- m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[
+ m, _, _, _, _, _, _, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[
2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13]
ux, uy, uz = u[0], u[1], u[2]
- return np.matrix([
+ return np.array([
[0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0],
[0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0],
[0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0],
@@ -173,11 +176,11 @@ def A_func(self, x, u):
[0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]])
def B_func(self, x, u):
- m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[
+ m, _, _, _, _, _, _, q0, q1, q2, q3, _, _, _ = x[0], x[1], x[
2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13]
ux, uy, uz = u[0], u[1], u[2]
- return np.matrix([
+ return np.array([
[-0.01 * ux / np.sqrt(ux**2 + uy**2 + uz**2),
-0.01 * uy / np.sqrt(ux ** 2 + uy**2 + uz**2),
-0.01 * uz / np.sqrt(ux**2 + uy**2 + uz**2)],
@@ -195,8 +198,8 @@ def B_func(self, x, u):
[0, 0, 0],
[0, 0, 0],
[0, 0, 0],
- [0, 0, 1.00000000000000],
- [0, -1.00000000000000, 0]
+ [0, 0, 1.0],
+ [0, -1.0, 0]
])
def euler_to_quat(self, a):
@@ -219,14 +222,14 @@ def euler_to_quat(self, a):
return q
def skew(self, v):
- return np.matrix([
+ return np.array([
[0, -v[2], v[1]],
[v[2], 0, -v[0]],
[-v[1], v[0], 0]
])
def dir_cosine(self, q):
- return np.matrix([
+ return np.array([
[1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2]
+ q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])],
[2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2
@@ -236,7 +239,7 @@ def dir_cosine(self, q):
])
def omega(self, w):
- return np.matrix([
+ return np.array([
[0, -w[0], -w[1], -w[2]],
[w[0], 0, w[2], -w[1]],
[w[1], -w[2], 0, w[0]],
@@ -304,7 +307,7 @@ def get_constraints(self, X_v, U_v, X_last_p, U_last_p):
]
# linearized lower thrust constraint
- rhs = [U_last_p[:, k] / cvxpy.norm(U_last_p[:, k]) * U_v[:, k]
+ rhs = [U_last_p[:, k] / cvxpy.norm(U_last_p[:, k]) @ U_v[:, k]
for k in range(X_v.shape[1])]
constraints += [
self.T_min <= cvxpy.vstack(rhs)
@@ -460,11 +463,11 @@ def __init__(self, m, K):
# x_t+1 = A_*x_t+B_*U_t+C_*U_T+1*S_*sigma+zbar+nu
constraints += [
self.var['X'][:, k + 1] ==
- cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x)) *
+ cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x), order='F') @
self.var['X'][:, k] +
- cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u)) *
+ cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u), order='F') @
self.var['U'][:, k] +
- cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u)) *
+ cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u), order='F') @
self.var['U'][:, k + 1] +
self.par['S_bar'][:, k] * self.var['sigma'] +
self.par['z_bar'][:, k] +
@@ -531,8 +534,10 @@ def get_variable(self, name):
def solve(self, **kwargs):
error = False
try:
- self.prob.solve(verbose=verbose_solver,
- solver=solver)
+ with warnings.catch_warnings(): # For User warning from solver
+ warnings.simplefilter('ignore')
+ self.prob.solve(verbose=verbose_solver,
+ solver=solver)
except cvxpy.SolverError:
error = True
@@ -566,7 +571,10 @@ def axis3d_equal(X, Y, Z, ax):
def plot_animation(X, U): # pragma: no cover
fig = plt.figure()
- ax = fig.gca(projection='3d')
+ ax = fig.add_subplot(projection='3d')
+ # for stopping simulation with the esc key.
+ fig.canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
for k in range(K):
plt.cla()
@@ -603,9 +611,9 @@ def plot_animation(X, U): # pragma: no cover
plt.pause(0.5)
-def main():
+def main(rng=None):
print("start!!")
- m = Rocket_Model_6DoF()
+ m = Rocket_Model_6DoF(rng)
# state and input list
X = np.empty(shape=[m.n_x, K])
diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py
index 2bcc33d0f7..9047c13851 100644
--- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py
+++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py
@@ -34,7 +34,7 @@ def detect_collision(line_seg, circle):
"""
Determines whether a line segment (arm link) is in contact
with a circle (obstacle).
- Credit to: http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html
+ Credit to: https://web.archive.org/web/20200130224918/http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html
Args:
line_seg: List of coordinates of line segment endpoints e.g. [[1, 1], [2, 2]]
circle: List of circle coordinates and radius e.g. [0, 0, 0.5] is a circle centered
@@ -105,7 +105,7 @@ def astar_torus(grid, start_node, goal_node):
Args:
grid: An occupancy grid (ndarray)
- start_node: Initial joint configuation (tuple)
+ start_node: Initial joint configuration (tuple)
goal_node: Goal joint configuration (tuple)
Returns:
@@ -158,10 +158,13 @@ def astar_torus(grid, start_node, goal_node):
while parent_map[route[0][0]][route[0][1]] != ():
route.insert(0, parent_map[route[0][0]][route[0][1]])
- print("The route found covers %d grid cells." % len(route))
+ print(f"The route found covers {len(route)} grid cells.")
for i in range(1, len(route)):
grid[route[i]] = 6
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
plt.show()
plt.pause(1e-2)
@@ -200,16 +203,16 @@ def calc_heuristic_map(M, goal_node):
for i in range(heuristic_map.shape[0]):
for j in range(heuristic_map.shape[1]):
heuristic_map[i, j] = min(heuristic_map[i, j],
- i + 1 + heuristic_map[M - 1, j],
- M - i + heuristic_map[0, j],
- j + 1 + heuristic_map[i, M - 1],
- M - j + heuristic_map[i, 0]
+ M - i - 1 + heuristic_map[M - 1, j],
+ i + heuristic_map[0, j],
+ M - j - 1 + heuristic_map[i, M - 1],
+ j + heuristic_map[i, 0]
)
return heuristic_map
-class NLinkArm(object):
+class NLinkArm:
"""
Class for controlling and plotting a planar arm with an arbitrary number of links.
"""
@@ -262,4 +265,4 @@ def plot(self, obstacles=[]): # pragma: no cover
if __name__ == '__main__':
- main()
\ No newline at end of file
+ main()
diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py
index b8c1ce89e9..f5d435082a 100644
--- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py
+++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py
@@ -34,7 +34,7 @@ def main():
goal = (58, 56)
grid = get_occupancy_grid(arm, obstacles)
route = astar_torus(grid, start, goal)
- if len(route) >= 0:
+ if route:
animate(grid, arm, route)
@@ -66,7 +66,7 @@ def detect_collision(line_seg, circle):
"""
Determines whether a line segment (arm link) is in contact
with a circle (obstacle).
- Credit to: http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html
+ Credit to: https://web.archive.org/web/20200130224918/http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html
Args:
line_seg: List of coordinates of line segment endpoints e.g. [[1, 1], [2, 2]]
circle: List of circle coordinates and radius e.g. [0, 0, 0.5] is a circle centered
@@ -105,7 +105,7 @@ def get_occupancy_grid(arm, obstacles):
Args:
arm: An instance of NLinkArm
obstacles: A list of obstacles, with each obstacle defined as a list
- of xy coordinates and a radius.
+ of xy coordinates and a radius.
Returns:
Occupancy grid in joint space
@@ -136,7 +136,7 @@ def astar_torus(grid, start_node, goal_node):
Args:
grid: An occupancy grid (ndarray)
- start_node: Initial joint configuation (tuple)
+ start_node: Initial joint configuration (tuple)
goal_node: Goal joint configuration (tuple)
Returns:
@@ -189,10 +189,13 @@ def astar_torus(grid, start_node, goal_node):
while parent_map[route[0][0]][route[0][1]] != ():
route.insert(0, parent_map[route[0][0]][route[0][1]])
- print("The route found covers %d grid cells." % len(route))
+ print(f"The route found covers {len(route)} grid cells.")
for i in range(1, len(route)):
grid[route[i]] = 6
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
plt.show()
plt.pause(1e-2)
@@ -231,16 +234,16 @@ def calc_heuristic_map(M, goal_node):
for i in range(heuristic_map.shape[0]):
for j in range(heuristic_map.shape[1]):
heuristic_map[i, j] = min(heuristic_map[i, j],
- i + 1 + heuristic_map[M - 1, j],
- M - i + heuristic_map[0, j],
- j + 1 + heuristic_map[i, M - 1],
- M - j + heuristic_map[i, 0]
+ M - i - 1 + heuristic_map[M - 1, j],
+ i + heuristic_map[0, j],
+ M - j - 1 + heuristic_map[i, M - 1],
+ j + heuristic_map[i, 0]
)
return heuristic_map
-class NLinkArm(object):
+class NLinkArm:
"""
Class for controlling and plotting a planar arm with an arbitrary number of links.
"""
diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py
new file mode 100644
index 0000000000..0459e234b2
--- /dev/null
+++ b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py
@@ -0,0 +1,215 @@
+"""
+Class of n-link arm in 3D
+Author: Takayuki Murooka (takayuki5168)
+"""
+import numpy as np
+import math
+from mpl_toolkits.mplot3d import Axes3D
+import matplotlib.pyplot as plt
+
+
+class Link:
+ def __init__(self, dh_params):
+ self.dh_params_ = dh_params
+
+ def transformation_matrix(self):
+ theta = self.dh_params_[0]
+ alpha = self.dh_params_[1]
+ a = self.dh_params_[2]
+ d = self.dh_params_[3]
+
+ st = math.sin(theta)
+ ct = math.cos(theta)
+ sa = math.sin(alpha)
+ ca = math.cos(alpha)
+ trans = np.array([[ct, -st * ca, st * sa, a * ct],
+ [st, ct * ca, -ct * sa, a * st],
+ [0, sa, ca, d],
+ [0, 0, 0, 1]])
+
+ return trans
+
+ @staticmethod
+ def basic_jacobian(trans_prev, ee_pos):
+ pos_prev = np.array(
+ [trans_prev[0, 3], trans_prev[1, 3], trans_prev[2, 3]])
+ z_axis_prev = np.array(
+ [trans_prev[0, 2], trans_prev[1, 2], trans_prev[2, 2]])
+
+ basic_jacobian = np.hstack(
+ (np.cross(z_axis_prev, ee_pos - pos_prev), z_axis_prev))
+ return basic_jacobian
+
+
+class NLinkArm:
+ def __init__(self, dh_params_list):
+ self.link_list = []
+ for i in range(len(dh_params_list)):
+ self.link_list.append(Link(dh_params_list[i]))
+
+ def transformation_matrix(self):
+ trans = np.identity(4)
+ for i in range(len(self.link_list)):
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+ return trans
+
+ def forward_kinematics(self, plot=False):
+ trans = self.transformation_matrix()
+
+ x = trans[0, 3]
+ y = trans[1, 3]
+ z = trans[2, 3]
+ alpha, beta, gamma = self.euler_angle()
+
+ if plot:
+ self.fig = plt.figure()
+ self.ax = Axes3D(self.fig, auto_add_to_figure=False)
+ self.fig.add_axes(self.ax)
+
+ x_list = []
+ y_list = []
+ z_list = []
+
+ trans = np.identity(4)
+
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+ for i in range(len(self.link_list)):
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+
+ self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4,
+ mew=0.5)
+ self.ax.plot([0], [0], [0], "o")
+
+ self.ax.set_xlim(-1, 1)
+ self.ax.set_ylim(-1, 1)
+ self.ax.set_zlim(-1, 1)
+
+ plt.show()
+
+ return [x, y, z, alpha, beta, gamma]
+
+ def basic_jacobian(self):
+ ee_pos = self.forward_kinematics()[0:3]
+ basic_jacobian_mat = []
+
+ trans = np.identity(4)
+ for i in range(len(self.link_list)):
+ basic_jacobian_mat.append(
+ self.link_list[i].basic_jacobian(trans, ee_pos))
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+
+ return np.array(basic_jacobian_mat).T
+
+ def inverse_kinematics(self, ref_ee_pose, plot=False):
+ for cnt in range(500):
+ ee_pose = self.forward_kinematics()
+ diff_pose = np.array(ref_ee_pose) - ee_pose
+
+ basic_jacobian_mat = self.basic_jacobian()
+ alpha, beta, gamma = self.euler_angle()
+
+ K_zyz = np.array(
+ [[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)],
+ [0, math.cos(alpha), math.sin(alpha) * math.sin(beta)],
+ [1, 0, math.cos(beta)]])
+ K_alpha = np.identity(6)
+ K_alpha[3:, 3:] = K_zyz
+
+ theta_dot = np.dot(
+ np.dot(np.linalg.pinv(basic_jacobian_mat), K_alpha),
+ np.array(diff_pose))
+ self.update_joint_angles(theta_dot / 100.)
+
+ if plot:
+ self.fig = plt.figure()
+ self.ax = Axes3D(self.fig, auto_add_to_figure=False)
+ self.fig.add_axes(self.ax)
+
+ x_list = []
+ y_list = []
+ z_list = []
+
+ trans = np.identity(4)
+
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+ for i in range(len(self.link_list)):
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+
+ self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4,
+ mew=0.5)
+ self.ax.plot([0], [0], [0], "o")
+
+ self.ax.set_xlim(-1, 1)
+ self.ax.set_ylim(-1, 1)
+ self.ax.set_zlim(-1, 1)
+
+ self.ax.plot([ref_ee_pose[0]], [ref_ee_pose[1]], [ref_ee_pose[2]],
+ "o")
+ plt.show()
+
+ def euler_angle(self):
+ trans = self.transformation_matrix()
+
+ alpha = math.atan2(trans[1][2], trans[0][2])
+ if not (-math.pi / 2 <= alpha <= math.pi / 2):
+ alpha = math.atan2(trans[1][2], trans[0][2]) + math.pi
+ if not (-math.pi / 2 <= alpha <= math.pi / 2):
+ alpha = math.atan2(trans[1][2], trans[0][2]) - math.pi
+ beta = math.atan2(
+ trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha),
+ trans[2][2])
+ gamma = math.atan2(
+ -trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha),
+ -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha))
+
+ return alpha, beta, gamma
+
+ def set_joint_angles(self, joint_angle_list):
+ for i in range(len(self.link_list)):
+ self.link_list[i].dh_params_[0] = joint_angle_list[i]
+
+ def update_joint_angles(self, diff_joint_angle_list):
+ for i in range(len(self.link_list)):
+ self.link_list[i].dh_params_[0] += diff_joint_angle_list[i]
+
+ def plot(self):
+ self.fig = plt.figure()
+ self.ax = Axes3D(self.fig)
+
+ x_list = []
+ y_list = []
+ z_list = []
+
+ trans = np.identity(4)
+
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+ for i in range(len(self.link_list)):
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+
+ self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4,
+ mew=0.5)
+ self.ax.plot([0], [0], [0], "o")
+
+ self.ax.set_xlabel("x")
+ self.ax.set_ylabel("y")
+ self.ax.set_zlabel("z")
+
+ self.ax.set_xlim(-1, 1)
+ self.ax.set_ylim(-1, 1)
+ self.ax.set_zlim(-1, 1)
+ plt.show()
diff --git a/ArmNavigation/n_joint_arm_3d/__init__.py b/ArmNavigation/n_joint_arm_3d/__init__.py
new file mode 100644
index 0000000000..2194d4c303
--- /dev/null
+++ b/ArmNavigation/n_joint_arm_3d/__init__.py
@@ -0,0 +1,3 @@
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent))
diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py
new file mode 100644
index 0000000000..f9caace300
--- /dev/null
+++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py
@@ -0,0 +1,33 @@
+"""
+Forward Kinematics for an n-link arm in 3D
+Author: Takayuki Murooka (takayuki5168)
+"""
+import math
+from NLinkArm3d import NLinkArm
+import random
+
+
+def random_val(min_val, max_val):
+ return min_val + random.random() * (max_val - min_val)
+
+
+def main():
+ print("Start solving Forward Kinematics 10 times")
+ # init NLinkArm with Denavit-Hartenberg parameters of PR2
+ n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.],
+ [math.pi / 2, math.pi / 2, 0., 0.],
+ [0., -math.pi / 2, 0., .4],
+ [0., math.pi / 2, 0., 0.],
+ [0., -math.pi / 2, 0., .321],
+ [0., math.pi / 2, 0., 0.],
+ [0., 0., 0., 0.]])
+ # execute FK 10 times
+ for _ in range(10):
+ n_link_arm.set_joint_angles(
+ [random_val(-1, 1) for _ in range(len(n_link_arm.link_list))])
+
+ n_link_arm.forward_kinematics(plot=True)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py
new file mode 100644
index 0000000000..91f6f1bba0
--- /dev/null
+++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py
@@ -0,0 +1,35 @@
+"""
+Inverse Kinematics for an n-link arm in 3D
+Author: Takayuki Murooka (takayuki5168)
+"""
+import math
+from NLinkArm3d import NLinkArm
+import random
+
+
+def random_val(min_val, max_val):
+ return min_val + random.random() * (max_val - min_val)
+
+
+def main():
+ print("Start solving Inverse Kinematics 10 times")
+ # init NLinkArm with Denavit-Hartenberg parameters of PR2
+ n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.],
+ [math.pi / 2, math.pi / 2, 0., 0.],
+ [0., -math.pi / 2, 0., .4],
+ [0., math.pi / 2, 0., 0.],
+ [0., -math.pi / 2, 0., .321],
+ [0., math.pi / 2, 0., 0.],
+ [0., 0., 0., 0.]])
+ # execute IK 10 times
+ for _ in range(10):
+ n_link_arm.inverse_kinematics([random_val(-0.5, 0.5),
+ random_val(-0.5, 0.5),
+ random_val(-0.5, 0.5),
+ random_val(-0.5, 0.5),
+ random_val(-0.5, 0.5),
+ random_val(-0.5, 0.5)], plot=True)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py
index 8ed12c565b..854ade9038 100644
--- a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py
+++ b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py
@@ -51,6 +51,9 @@ def update_points(self):
def plot(self): # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
for i in range(self.n_links + 1):
if i is not self.n_links:
diff --git a/PathTracking/.gitignore b/ArmNavigation/n_joint_arm_to_point_control/__init__.py
similarity index 100%
rename from PathTracking/.gitignore
rename to ArmNavigation/n_joint_arm_to_point_control/__init__.py
diff --git a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py
index b232ab33f3..a237523336 100644
--- a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py
+++ b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py
@@ -4,9 +4,14 @@
Author: Daniel Ingram (daniel-s-ingram)
Atsushi Sakai (@Atsushi_twi)
"""
-import numpy as np
-from NLinkArm import NLinkArm
+import sys
+from pathlib import Path
+sys.path.append(str(Path(__file__).parent.parent.parent))
+
+import numpy as np
+from ArmNavigation.n_joint_arm_to_point_control.NLinkArm import NLinkArm
+from utils.angle import angle_mod
# Simulation parameters
Kp = 2
@@ -148,16 +153,16 @@ def jacobian_inverse(link_lengths, joint_angles):
def distance_to_goal(current_pos, goal_pos):
x_diff = goal_pos[0] - current_pos[0]
y_diff = goal_pos[1] - current_pos[1]
- return np.array([x_diff, y_diff]).T, np.math.sqrt(x_diff**2 + y_diff**2)
+ return np.array([x_diff, y_diff]).T, np.hypot(x_diff, y_diff)
def ang_diff(theta1, theta2):
"""
Returns the difference between two angles in the range -pi to +pi
"""
- return (theta1 - theta2 + np.pi) % (2 * np.pi) - np.pi
+ return angle_mod(theta1 - theta2)
if __name__ == '__main__':
# main()
- animation()
\ No newline at end of file
+ animation()
diff --git a/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py
new file mode 100755
index 0000000000..3bc2a5ec1d
--- /dev/null
+++ b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py
@@ -0,0 +1,405 @@
+"""
+RRT* path planner for a seven joint arm
+Author: Mahyar Abdeetedal (mahyaret)
+"""
+import math
+import random
+import numpy as np
+import matplotlib.pyplot as plt
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+
+from n_joint_arm_3d.NLinkArm3d import NLinkArm
+
+show_animation = True
+verbose = False
+
+
+class RobotArm(NLinkArm):
+ def get_points(self, joint_angle_list):
+ self.set_joint_angles(joint_angle_list)
+
+ x_list = []
+ y_list = []
+ z_list = []
+
+ trans = np.identity(4)
+
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+ for i in range(len(self.link_list)):
+ trans = np.dot(trans, self.link_list[i].transformation_matrix())
+ x_list.append(trans[0, 3])
+ y_list.append(trans[1, 3])
+ z_list.append(trans[2, 3])
+
+ return x_list, y_list, z_list
+
+
+class RRTStar:
+ """
+ Class for RRT Star planning
+ """
+
+ class Node:
+ def __init__(self, x):
+ self.x = x
+ self.parent = None
+ self.cost = 0.0
+
+ def __init__(self, start, goal, robot, obstacle_list, rand_area,
+ expand_dis=.30,
+ path_resolution=.1,
+ goal_sample_rate=20,
+ max_iter=300,
+ connect_circle_dist=50.0
+ ):
+ """
+ Setting Parameter
+
+ start:Start Position [q1,...,qn]
+ goal:Goal Position [q1,...,qn]
+ obstacleList:obstacle Positions [[x,y,z,size],...]
+ randArea:Random Sampling Area [min,max]
+
+ """
+ self.start = self.Node(start)
+ self.end = self.Node(goal)
+ self.dimension = len(start)
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.expand_dis = expand_dis
+ self.path_resolution = path_resolution
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.robot = robot
+ self.obstacle_list = obstacle_list
+ self.connect_circle_dist = connect_circle_dist
+ self.goal_node = self.Node(goal)
+ self.node_list = []
+ if show_animation:
+ self.ax = plt.axes(projection='3d')
+
+ def planning(self, animation=False, search_until_max_iter=False):
+ """
+ rrt star path planning
+
+ animation: flag for animation on or off
+ search_until_max_iter: search until max iteration for path
+ improving or not
+ """
+
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ if verbose:
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind],
+ rnd,
+ self.expand_dis)
+
+ if self.check_collision(new_node, self.robot, self.obstacle_list):
+ near_inds = self.find_near_nodes(new_node)
+ new_node = self.choose_parent(new_node, near_inds)
+ if new_node:
+ self.node_list.append(new_node)
+ self.rewire(new_node, near_inds)
+
+ if animation and i % 5 == 0 and self.dimension <= 3:
+ self.draw_graph(rnd)
+
+ if (not search_until_max_iter) and new_node:
+ last_index = self.search_best_goal_node()
+ if last_index is not None:
+ return self.generate_final_course(last_index)
+ if verbose:
+ print("reached max iteration")
+
+ last_index = self.search_best_goal_node()
+ if last_index is not None:
+ return self.generate_final_course(last_index)
+
+ return None
+
+ def choose_parent(self, new_node, near_inds):
+ if not near_inds:
+ return None
+
+ # search nearest cost in near_inds
+ costs = []
+ for i in near_inds:
+ near_node = self.node_list[i]
+ t_node = self.steer(near_node, new_node)
+ if t_node and self.check_collision(t_node,
+ self.robot,
+ self.obstacle_list):
+ costs.append(self.calc_new_cost(near_node, new_node))
+ else:
+ costs.append(float("inf")) # the cost of collision node
+ min_cost = min(costs)
+
+ if min_cost == float("inf"):
+ print("There is no good path.(min_cost is inf)")
+ return None
+
+ min_ind = near_inds[costs.index(min_cost)]
+ new_node = self.steer(self.node_list[min_ind], new_node)
+ new_node.parent = self.node_list[min_ind]
+ new_node.cost = min_cost
+
+ return new_node
+
+ def search_best_goal_node(self):
+ dist_to_goal_list = [self.calc_dist_to_goal(n.x)
+ for n in self.node_list]
+ goal_inds = [dist_to_goal_list.index(i)
+ for i in dist_to_goal_list if i <= self.expand_dis]
+
+ safe_goal_inds = []
+ for goal_ind in goal_inds:
+ t_node = self.steer(self.node_list[goal_ind], self.goal_node)
+ if self.check_collision(t_node, self.robot, self.obstacle_list):
+ safe_goal_inds.append(goal_ind)
+
+ if not safe_goal_inds:
+ return None
+
+ min_cost = min([self.node_list[i].cost for i in safe_goal_inds])
+ for i in safe_goal_inds:
+ if self.node_list[i].cost == min_cost:
+ return i
+
+ return None
+
+ def find_near_nodes(self, new_node):
+ nnode = len(self.node_list) + 1
+ r = self.connect_circle_dist * math.sqrt(math.log(nnode) / nnode)
+ # if expand_dist exists, search vertices in
+ # a range no more than expand_dist
+ if hasattr(self, 'expand_dis'):
+ r = min(r, self.expand_dis)
+ dist_list = [np.sum((np.array(node.x) - np.array(new_node.x)) ** 2)
+ for node in self.node_list]
+ near_inds = [dist_list.index(i) for i in dist_list if i <= r ** 2]
+ return near_inds
+
+ def rewire(self, new_node, near_inds):
+ for i in near_inds:
+ near_node = self.node_list[i]
+ edge_node = self.steer(new_node, near_node)
+ if not edge_node:
+ continue
+ edge_node.cost = self.calc_new_cost(new_node, near_node)
+
+ no_collision = self.check_collision(edge_node,
+ self.robot,
+ self.obstacle_list)
+ improved_cost = near_node.cost > edge_node.cost
+
+ if no_collision and improved_cost:
+ self.node_list[i] = edge_node
+ self.propagate_cost_to_leaves(new_node)
+
+ def calc_new_cost(self, from_node, to_node):
+ d, _, _ = self.calc_distance_and_angle(from_node, to_node)
+ return from_node.cost + d
+
+ def propagate_cost_to_leaves(self, parent_node):
+
+ for node in self.node_list:
+ if node.parent == parent_node:
+ node.cost = self.calc_new_cost(parent_node, node)
+ self.propagate_cost_to_leaves(node)
+
+ def generate_final_course(self, goal_ind):
+ path = [self.end.x]
+ node = self.node_list[goal_ind]
+ while node.parent is not None:
+ path.append(node.x)
+ node = node.parent
+ path.append(node.x)
+ reversed(path)
+ return path
+
+ def calc_dist_to_goal(self, x):
+ distance = np.linalg.norm(np.array(x) - np.array(self.end.x))
+ return distance
+
+ def get_random_node(self):
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = self.Node(np.random.uniform(self.min_rand,
+ self.max_rand,
+ self.dimension))
+ else: # goal point sampling
+ rnd = self.Node(self.end.x)
+ return rnd
+
+ def steer(self, from_node, to_node, extend_length=float("inf")):
+ new_node = self.Node(list(from_node.x))
+ d, phi, theta = self.calc_distance_and_angle(new_node, to_node)
+
+ new_node.path_x = [list(new_node.x)]
+
+ if extend_length > d:
+ extend_length = d
+
+ n_expand = math.floor(extend_length / self.path_resolution)
+
+ start, end = np.array(from_node.x), np.array(to_node.x)
+ v = end - start
+ u = v / (np.sqrt(np.sum(v ** 2)))
+ for _ in range(n_expand):
+ new_node.x += u * self.path_resolution
+ new_node.path_x.append(list(new_node.x))
+
+ d, _, _ = self.calc_distance_and_angle(new_node, to_node)
+ if d <= self.path_resolution:
+ new_node.path_x.append(list(to_node.x))
+
+ new_node.parent = from_node
+
+ return new_node
+
+ def draw_graph(self, rnd=None):
+ plt.cla()
+ self.ax.axis([-1, 1, -1, 1, -1, 1])
+ self.ax.set_zlim(0, 1)
+ self.ax.grid(True)
+ for (ox, oy, oz, size) in self.obstacle_list:
+ self.plot_sphere(self.ax, ox, oy, oz, size=size)
+ if self.dimension > 3:
+ return self.ax
+ if rnd is not None:
+ self.ax.plot([rnd.x[0]], [rnd.x[1]], [rnd.x[2]], "^k")
+ for node in self.node_list:
+ if node.parent:
+ path = np.array(node.path_x)
+ plt.plot(path[:, 0], path[:, 1], path[:, 2], "-g")
+ self.ax.plot([self.start.x[0]], [self.start.x[1]],
+ [self.start.x[2]], "xr")
+ self.ax.plot([self.end.x[0]], [self.end.x[1]], [self.end.x[2]], "xr")
+ plt.pause(0.01)
+ return self.ax
+
+ @staticmethod
+ def get_nearest_node_index(node_list, rnd_node):
+ dlist = [np.sum((np.array(node.x) - np.array(rnd_node.x))**2)
+ for node in node_list]
+ minind = dlist.index(min(dlist))
+
+ return minind
+
+ @staticmethod
+ def plot_sphere(ax, x, y, z, size=1, color="k"):
+ u, v = np.mgrid[0:2*np.pi:20j, 0:np.pi:10j]
+ xl = x+size*np.cos(u)*np.sin(v)
+ yl = y+size*np.sin(u)*np.sin(v)
+ zl = z+size*np.cos(v)
+ ax.plot_wireframe(xl, yl, zl, color=color)
+
+ @staticmethod
+ def calc_distance_and_angle(from_node, to_node):
+ dx = to_node.x[0] - from_node.x[0]
+ dy = to_node.x[1] - from_node.x[1]
+ dz = to_node.x[2] - from_node.x[2]
+ d = np.sqrt(np.sum((np.array(to_node.x) - np.array(from_node.x))**2))
+ phi = math.atan2(dy, dx)
+ theta = math.atan2(math.hypot(dx, dy), dz)
+ return d, phi, theta
+
+ @staticmethod
+ def calc_distance_and_angle2(from_node, to_node):
+ dx = to_node.x[0] - from_node.x[0]
+ dy = to_node.x[1] - from_node.x[1]
+ dz = to_node.x[2] - from_node.x[2]
+ d = math.sqrt(dx**2 + dy**2 + dz**2)
+ phi = math.atan2(dy, dx)
+ theta = math.atan2(math.hypot(dx, dy), dz)
+ return d, phi, theta
+
+ @staticmethod
+ def check_collision(node, robot, obstacleList):
+
+ if node is None:
+ return False
+
+ for (ox, oy, oz, size) in obstacleList:
+ for x in node.path_x:
+ x_list, y_list, z_list = robot.get_points(x)
+ dx_list = [ox - x_point for x_point in x_list]
+ dy_list = [oy - y_point for y_point in y_list]
+ dz_list = [oz - z_point for z_point in z_list]
+ d_list = [dx * dx + dy * dy + dz * dz
+ for (dx, dy, dz) in zip(dx_list,
+ dy_list,
+ dz_list)]
+
+ if min(d_list) <= size ** 2:
+ return False # collision
+
+ return True # safe
+
+
+def main():
+ print("Start " + __file__)
+
+ # init NLinkArm with Denavit-Hartenberg parameters of panda
+ # https://frankaemika.github.io/docs/control_parameters.html
+ # [theta, alpha, a, d]
+ seven_joint_arm = RobotArm([[0., math.pi/2., 0., .333],
+ [0., -math.pi/2., 0., 0.],
+ [0., math.pi/2., 0.0825, 0.3160],
+ [0., -math.pi/2., -0.0825, 0.],
+ [0., math.pi/2., 0., 0.3840],
+ [0., math.pi/2., 0.088, 0.],
+ [0., 0., 0., 0.107]])
+ # ====Search Path with RRT====
+ obstacle_list = [
+ (-.3, -.3, .7, .1),
+ (.0, -.3, .7, .1),
+ (.2, -.1, .3, .15),
+ ] # [x,y,size(radius)]
+ start = [0 for _ in range(len(seven_joint_arm.link_list))]
+ end = [1.5 for _ in range(len(seven_joint_arm.link_list))]
+ # Set Initial parameters
+ rrt_star = RRTStar(start=start,
+ goal=end,
+ rand_area=[0, 2],
+ max_iter=200,
+ robot=seven_joint_arm,
+ obstacle_list=obstacle_list)
+ path = rrt_star.planning(animation=show_animation,
+ search_until_max_iter=False)
+
+ if path is None:
+ print("Cannot find path.")
+ else:
+ print("Found path!")
+
+ # Draw final path
+ if show_animation:
+ ax = rrt_star.draw_graph()
+
+ # Plot final configuration
+ x_points, y_points, z_points = seven_joint_arm.get_points(path[-1])
+ ax.plot([x for x in x_points],
+ [y for y in y_points],
+ [z for z in z_points],
+ "o-", color="red", ms=5, mew=0.5)
+
+ for i, q in enumerate(path):
+ x_points, y_points, z_points = seven_joint_arm.get_points(q)
+ ax.plot([x for x in x_points],
+ [y for y in y_points],
+ [z for z in z_points],
+ "o-", color="grey", ms=4, mew=0.5)
+ plt.pause(0.1)
+
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb b/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb
deleted file mode 100644
index a96f0ea2f4..0000000000
--- a/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb
+++ /dev/null
@@ -1,423 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Two joint arm to point control\n",
- "\n",
- "\n",
- "\n",
- "This is two joint arm to a point control simulation.\n",
- "\n",
- "This is a interactive simulation.\n",
- "\n",
- "You can set the goal position of the end effector with left-click on the ploting area.\n",
- "\n",
- "\n",
- "\n",
- "### Inverse Kinematics for a Planar Two-Link Robotic Arm\n",
- "\n",
- "A classic problem with robotic arms is getting the end-effector, the mechanism at the end of the arm responsible for manipulating the environment, to where you need it to be. Maybe the end-effector is a gripper and maybe you want to pick up an object and maybe you know where that object is relative to the robot - but you cannot tell the end-effector where to go directly. Instead, you have to determine the joint angles that get the end-effector to where you want it to be. This problem is known as inverse kinematics.\n",
- "\n",
- "Credit for this solution goes to: https://robotacademy.net.au/lesson/inverse-kinematics-for-a-2-joint-robot-arm-using-geometry/\n",
- "\n",
- "First, let's define a class to make plotting our arm easier.\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [],
- "source": [
- "%matplotlib inline\n",
- "from math import cos, sin\n",
- "import numpy as np\n",
- "import matplotlib.pyplot as plt\n",
- "\n",
- "class TwoLinkArm:\n",
- " def __init__(self, joint_angles=[0, 0]):\n",
- " self.shoulder = np.array([0, 0])\n",
- " self.link_lengths = [1, 1]\n",
- " self.update_joints(joint_angles)\n",
- " \n",
- " def update_joints(self, joint_angles):\n",
- " self.joint_angles = joint_angles\n",
- " self.forward_kinematics()\n",
- " \n",
- " def forward_kinematics(self):\n",
- " theta0 = self.joint_angles[0]\n",
- " theta1 = self.joint_angles[1]\n",
- " l0 = self.link_lengths[0]\n",
- " l1 = self.link_lengths[1]\n",
- " self.elbow = self.shoulder + np.array([l0*cos(theta0), l0*sin(theta0)])\n",
- " self.wrist = self.elbow + np.array([l1*cos(theta0 + theta1), l1*sin(theta0 + theta1)])\n",
- " \n",
- " def plot(self):\n",
- " plt.plot([self.shoulder[0], self.elbow[0]],\n",
- " [self.shoulder[1], self.elbow[1]],\n",
- " 'r-')\n",
- " plt.plot([self.elbow[0], self.wrist[0]],\n",
- " [self.elbow[1], self.wrist[1]],\n",
- " 'r-')\n",
- " plt.plot(self.shoulder[0], self.shoulder[1], 'ko')\n",
- " plt.plot(self.elbow[0], self.elbow[1], 'ko')\n",
- " plt.plot(self.wrist[0], self.wrist[1], 'ko')"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Let's also define a function to make it easier to draw an angle on our diagram."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [],
- "source": [
- "from math import sqrt\n",
- "\n",
- "def transform_points(points, theta, origin):\n",
- " T = np.array([[cos(theta), -sin(theta), origin[0]],\n",
- " [sin(theta), cos(theta), origin[1]],\n",
- " [0, 0, 1]])\n",
- " return np.matmul(T, np.array(points))\n",
- "\n",
- "def draw_angle(angle, offset=0, origin=[0, 0], r=0.5, n_points=100):\n",
- " x_start = r*cos(angle)\n",
- " x_end = r\n",
- " dx = (x_end - x_start)/(n_points-1)\n",
- " coords = [[0 for _ in range(n_points)] for _ in range(3)]\n",
- " x = x_start\n",
- " for i in range(n_points-1):\n",
- " y = sqrt(r**2 - x**2)\n",
- " coords[0][i] = x\n",
- " coords[1][i] = y\n",
- " coords[2][i] = 1\n",
- " x += dx\n",
- " coords[0][-1] = r\n",
- " coords[2][-1] = 1\n",
- " coords = transform_points(coords, offset, origin)\n",
- " plt.plot(coords[0], coords[1], 'k-')"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Okay, we now have a TwoLinkArm class to help us draw the arm, which we'll do several times during our derivation. Notice there is a method called forward_kinematics - forward kinematics specifies the end-effector position given the joint angles and link lengths. Forward kinematics is easier than inverse kinematics."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "arm = TwoLinkArm()\n",
- "\n",
- "theta0 = 0.5\n",
- "theta1 = 1\n",
- "\n",
- "arm.update_joints([theta0, theta1])\n",
- "arm.plot()\n",
- "\n",
- "def label_diagram():\n",
- " plt.plot([0, 0.5], [0, 0], 'k--')\n",
- " plt.plot([arm.elbow[0], arm.elbow[0]+0.5*cos(theta0)],\n",
- " [arm.elbow[1], arm.elbow[1]+0.5*sin(theta0)],\n",
- " 'k--')\n",
- " \n",
- " draw_angle(theta0, r=0.25)\n",
- " draw_angle(theta1, offset=theta0, origin=[arm.elbow[0], arm.elbow[1]], r=0.25)\n",
- " \n",
- " plt.annotate(\"$l_0$\", xy=(0.5, 0.4), size=15, color=\"r\")\n",
- " plt.annotate(\"$l_1$\", xy=(0.8, 1), size=15, color=\"r\")\n",
- " \n",
- " plt.annotate(r\"$\\theta_0$\", xy=(0.35, 0.05), size=15)\n",
- " plt.annotate(r\"$\\theta_1$\", xy=(1, 0.8), size=15)\n",
- "\n",
- "label_diagram()\n",
- "\n",
- "plt.annotate(\"Shoulder\", xy=(arm.shoulder[0], arm.shoulder[1]), xytext=(0.15, 0.5),\n",
- " arrowprops=dict(facecolor='black', shrink=0.05))\n",
- "plt.annotate(\"Elbow\", xy=(arm.elbow[0], arm.elbow[1]), xytext=(1.25, 0.25),\n",
- " arrowprops=dict(facecolor='black', shrink=0.05))\n",
- "plt.annotate(\"Wrist\", xy=(arm.wrist[0], arm.wrist[1]), xytext=(1, 1.75),\n",
- " arrowprops=dict(facecolor='black', shrink=0.05))\n",
- "\n",
- "plt.axis(\"equal\")\n",
- "\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "It's common to name arm joints anatomically, hence the names shoulder , elbow , and wrist . In this example, the wrist is not itself a joint, but we can consider it to be our end-effector. If we constrain the shoulder to the origin, we can write the forward kinematics for the elbow and the wrist.\n",
- "\n",
- "$elbow_x = l_0\\cos(\\theta_0)$ \n",
- "$elbow_y = l_0\\sin(\\theta_0)$ \n",
- "\n",
- "$wrist_x = elbow_x + l_1\\cos(\\theta_0+\\theta_1) = l_0\\cos(\\theta_0) + l_1\\cos(\\theta_0+\\theta_1)$ \n",
- "$wrist_y = elbow_y + l_1\\sin(\\theta_0+\\theta_1) = l_0\\sin(\\theta_0) + l_1\\sin(\\theta_0+\\theta_1)$ \n",
- "\n",
- "Since the wrist is our end-effector, let's just call its coordinates $x$ and $y$ . The forward kinematics for our end-effector is then\n",
- "\n",
- "$x = l_0\\cos(\\theta_0) + l_1\\cos(\\theta_0+\\theta_1)$ \n",
- "$y = l_0\\sin(\\theta_0) + l_1\\sin(\\theta_0+\\theta_1)$ \n",
- "\n",
- "A first attempt to find the joint angles $\\theta_0$ and $\\theta_1$ that would get our end-effector to the desired coordinates $x$ and $y$ might be to try solving the forward kinematics for $\\theta_0$ and $\\theta_1$, but that would be the wrong move. An easier path involves going back to the geometry of the arm."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 4,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "from math import pi\n",
- "\n",
- "arm.plot()\n",
- "label_diagram()\n",
- "\n",
- "plt.plot([0, arm.wrist[0]],\n",
- " [0, arm.wrist[1]],\n",
- " 'k--')\n",
- "\n",
- "plt.plot([arm.wrist[0], arm.wrist[0]],\n",
- " [0, arm.wrist[1]],\n",
- " 'b--')\n",
- "plt.plot([0, arm.wrist[0]],\n",
- " [0, 0],\n",
- " 'b--')\n",
- "\n",
- "plt.annotate(\"$x$\", xy=(0.6, 0.05), size=15, color=\"b\")\n",
- "plt.annotate(\"$y$\", xy=(1, 0.2), size=15, color=\"b\")\n",
- "plt.annotate(\"$r$\", xy=(0.45, 0.9), size=15)\n",
- "plt.annotate(r\"$\\alpha$\", xy=(0.75, 0.6), size=15)\n",
- "\n",
- "alpha = pi-theta1\n",
- "draw_angle(alpha, offset=theta0+theta1, origin=[arm.elbow[0], arm.elbow[1]], r=0.1)\n",
- "\n",
- "plt.axis(\"equal\")\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "The distance from the end-effector to the robot base (shoulder joint) is $r$ and can be written in terms of the end-effector position using the Pythagorean Theorem.\n",
- "\n",
- "$r^2$ = $x^2 + y^2$\n",
- "\n",
- "Then, by the law of cosines, $r$2 can also be written as:\n",
- "\n",
- "$r^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\alpha)$\n",
- "\n",
- "Because $\\alpha$ can be written as $\\pi - \\theta_1$, we can relate the desired end-effector position to one of our joint angles, $\\theta_1$.\n",
- "\n",
- "$x^2 + y^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\alpha)$ \n",
- " \n",
- "$x^2 + y^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\pi-\\theta_1)$ \n",
- " \n",
- "$2l_0l_1\\cos(\\pi-\\theta_1) = l_0^2 + l_1^2 - x^2 - y^2$ \n",
- " \n",
- "$\\cos(\\pi-\\theta_1) = \\frac{l_0^2 + l_1^2 - x^2 - y^2}{2l_0l_1}$ \n",
- "$~$ \n",
- "$~$ \n",
- "$\\cos(\\pi-\\theta_1) = -cos(\\theta_1)$ is a trigonometric identity, so we can also write\n",
- "\n",
- "$\\cos(\\theta_1) = \\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1}$ \n",
- "\n",
- "which leads us to an equation for $\\theta_1$ in terms of the link lengths and the desired end-effector position!\n",
- "\n",
- "$\\theta_1 = \\cos^{-1}(\\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1})$ \n",
- "\n",
- "This is actually one of two possible solutions for $\\theta_1$, but we'll ignore the other possibility for now. This solution will lead us to the \"arm-down\" configuration of the arm, which is what's shown in the diagram. Now we'll derive an equation for $\\theta_0$ that depends on this value of $\\theta_1$."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "from math import atan2\n",
- "\n",
- "arm.plot()\n",
- "plt.plot([0, arm.wrist[0]],\n",
- " [0, arm.wrist[1]],\n",
- " 'k--')\n",
- "\n",
- "p = 1 + cos(theta1)\n",
- "plt.plot([arm.elbow[0], p*cos(theta0)],\n",
- " [arm.elbow[1], p*sin(theta0)],\n",
- " 'b--', linewidth=5)\n",
- "plt.plot([arm.wrist[0], p*cos(theta0)],\n",
- " [arm.wrist[1], p*sin(theta0)],\n",
- " 'b--', linewidth=5)\n",
- "\n",
- "beta = atan2(arm.wrist[1], arm.wrist[0])-theta0\n",
- "draw_angle(beta, offset=theta0, r=0.45)\n",
- "\n",
- "plt.annotate(r\"$\\beta$\", xy=(0.35, 0.35), size=15)\n",
- "plt.annotate(\"$r$\", xy=(0.45, 0.9), size=15)\n",
- "plt.annotate(r\"$l_1sin(\\theta_1)$\",xy=(1.25, 1.1), size=15, color=\"b\")\n",
- "plt.annotate(r\"$l_1cos(\\theta_1)$\",xy=(1.1, 0.4), size=15, color=\"b\")\n",
- "\n",
- "label_diagram()\n",
- "\n",
- "plt.axis(\"equal\")\n",
- "\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Consider the angle between the displacement vector $r$ and the first link $l_0$; let's call it $\\beta$. If we extend the first link to include the component of the second link in the same direction as the first, we form a right triangle with components $l_0+l_1cos(\\theta_1)$ and $l_1sin(\\theta_1)$, allowing us to express $\\beta$ as\n",
- " \n",
- "$\\beta = \\tan^{-1}(\\frac{l_1\\sin(\\theta_1)}{l_0+l_1\\cos(\\theta_1)})$ \n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "We now have an expression for this angle $\\beta$ in terms of one of our arm's joint angles. Now, can we relate $\\beta$ to $\\theta_0$? Yes!"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 6,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "arm.plot()\n",
- "label_diagram()\n",
- "plt.plot([0, arm.wrist[0]],\n",
- " [0, arm.wrist[1]],\n",
- " 'k--')\n",
- "\n",
- "plt.plot([arm.wrist[0], arm.wrist[0]],\n",
- " [0, arm.wrist[1]],\n",
- " 'b--')\n",
- "plt.plot([0, arm.wrist[0]],\n",
- " [0, 0],\n",
- " 'b--')\n",
- "\n",
- "gamma = atan2(arm.wrist[1], arm.wrist[0])\n",
- "draw_angle(beta, offset=theta0, r=0.2)\n",
- "draw_angle(gamma, r=0.6)\n",
- "\n",
- "plt.annotate(\"$x$\", xy=(0.7, 0.05), size=15, color=\"b\")\n",
- "plt.annotate(\"$y$\", xy=(1, 0.2), size=15, color=\"b\")\n",
- "plt.annotate(r\"$\\beta$\", xy=(0.2, 0.2), size=15)\n",
- "plt.annotate(r\"$\\gamma$\", xy=(0.6, 0.2), size=15)\n",
- "\n",
- "plt.axis(\"equal\")\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Our first joint angle $\\theta_0$ added to $\\beta$ gives us the angle between the positive $x$-axis and the displacement vector $r$; let's call this angle $\\gamma$.\n",
- "\n",
- "$\\gamma = \\theta_0+\\beta$ \n",
- "\n",
- "$\\theta_0$, our remaining joint angle, can then be expressed as \n",
- "\n",
- "$\\theta_0 = \\gamma-\\beta$ \n",
- "\n",
- "We already know $\\beta$. $\\gamma$ is simply the inverse tangent of $\\frac{y}{x}$, so we have an equation of $\\theta_0$! \n",
- "\n",
- "$\\theta_0 = \\tan^{-1}(\\frac{y}{x})-\\tan^{-1}(\\frac{l_1\\sin(\\theta_1)}{l_0+l_1\\cos(\\theta_1)})$"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "We now have the inverse kinematics for a planar two-link robotic arm. If you're planning on implementing this in a programming language, it's best to use the atan2 function, which is included in most math libraries and correctly accounts for the signs of $y$ and $x$. Notice that $\\theta_1$ must be calculated before $\\theta_0$.\n",
- "\n",
- "$\\theta_1 = \\cos^{-1}(\\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1})$ \n",
- "$\\theta_0 = atan2(y, x)-atan2(l_1\\sin(\\theta_1), l_0+l_1\\cos(\\theta_1))$"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.8"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py
index e674ae8ac2..09969c30be 100644
--- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py
+++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py
@@ -5,16 +5,20 @@
Author: Daniel Ingram (daniel-s-ingram)
Atsushi Sakai (@Atsushi_twi)
-Ref: P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7 p102
-- [Robotics, Vision and Control \| SpringerLink](https://link.springer.com/book/10.1007/978-3-642-20144-8)
+Reference: P. I. Corke, "Robotics, Vision & Control", Springer 2017,
+ ISBN 978-3-319-54413-7 p102
+- [Robotics, Vision and Control]
+(https://link.springer.com/book/10.1007/978-3-642-20144-8)
"""
import matplotlib.pyplot as plt
import numpy as np
+import math
+from utils.angle import angle_mod
-# Similation parameters
+# Simulation parameters
Kp = 15
dt = 0.01
@@ -34,34 +38,50 @@
def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0):
"""
Computes the inverse kinematics for a planar 2DOF arm
+ When out of bounds, rewrite x and y with last correct values
"""
+ global x, y
+ x_prev, y_prev = None, None
while True:
try:
- theta2_goal = np.arccos(
- (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2))
- theta1_goal = np.math.atan2(y, x) - np.math.atan2(l2 *
- np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal)))
+ if x is not None and y is not None:
+ x_prev = x
+ y_prev = y
+ if np.hypot(x, y) > (l1 + l2):
+ theta2_goal = 0
+ else:
+ theta2_goal = np.arccos(
+ (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2))
+ tmp = math.atan2(l2 * np.sin(theta2_goal),
+ (l1 + l2 * np.cos(theta2_goal)))
+ theta1_goal = math.atan2(y, x) - tmp
if theta1_goal < 0:
theta2_goal = -theta2_goal
- theta1_goal = np.math.atan2(
- y, x) - np.math.atan2(l2 * np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal)))
+ tmp = math.atan2(l2 * np.sin(theta2_goal),
+ (l1 + l2 * np.cos(theta2_goal)))
+ theta1_goal = math.atan2(y, x) - tmp
theta1 = theta1 + Kp * ang_diff(theta1_goal, theta1) * dt
theta2 = theta2 + Kp * ang_diff(theta2_goal, theta2) * dt
except ValueError as e:
- print("Unreachable goal")
+ print("Unreachable goal"+e)
+ except TypeError:
+ x = x_prev
+ y = y_prev
wrist = plot_arm(theta1, theta2, x, y)
# check goal
- d2goal = np.math.sqrt((wrist[0] - x)**2 + (wrist[1] - y)**2)
+ d2goal = None
+ if x is not None and y is not None:
+ d2goal = np.hypot(wrist[0] - x, wrist[1] - y)
if abs(d2goal) < GOAL_TH and x is not None:
return theta1, theta2
-def plot_arm(theta1, theta2, x, y): # pragma: no cover
+def plot_arm(theta1, theta2, target_x, target_y): # pragma: no cover
shoulder = np.array([0, 0])
elbow = shoulder + np.array([l1 * np.cos(theta1), l1 * np.sin(theta1)])
wrist = elbow + \
@@ -77,8 +97,8 @@ def plot_arm(theta1, theta2, x, y): # pragma: no cover
plt.plot(elbow[0], elbow[1], 'ro')
plt.plot(wrist[0], wrist[1], 'ro')
- plt.plot([wrist[0], x], [wrist[1], y], 'g--')
- plt.plot(x, y, 'g*')
+ plt.plot([wrist[0], target_x], [wrist[1], target_y], 'g--')
+ plt.plot(target_x, target_y, 'g*')
plt.xlim(-2, 2)
plt.ylim(-2, 2)
@@ -91,7 +111,7 @@ def plot_arm(theta1, theta2, x, y): # pragma: no cover
def ang_diff(theta1, theta2):
# Returns the difference between two angles in the range -pi to +pi
- return (theta1 - theta2 + np.pi) % (2 * np.pi) - np.pi
+ return angle_mod(theta1 - theta2)
def click(event): # pragma: no cover
@@ -114,6 +134,9 @@ def animation():
def main(): # pragma: no cover
fig = plt.figure()
fig.canvas.mpl_connect("button_press_event", click)
+ # for stopping simulation with the esc key.
+ fig.canvas.mpl_connect('key_release_event', lambda event: [
+ exit(0) if event.key == 'escape' else None])
two_joint_arm()
diff --git a/tests/.gitkeep b/Bipedal/bipedal_planner/__init__.py
similarity index 100%
rename from tests/.gitkeep
rename to Bipedal/bipedal_planner/__init__.py
diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py
index 3cf2936ee4..c34357df67 100644
--- a/Bipedal/bipedal_planner/bipedal_planner.py
+++ b/Bipedal/bipedal_planner/bipedal_planner.py
@@ -12,13 +12,17 @@
class BipedalPlanner(object):
def __init__(self):
+ self.act_p = [] # actual footstep positions
+ self.ref_p = [] # reference footstep positions
+ self.com_trajectory = []
self.ref_footsteps = None
self.g = 9.8
def set_ref_footsteps(self, ref_footsteps):
self.ref_footsteps = ref_footsteps
- def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c, time_width):
+ def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c,
+ time_width):
time_split = 100
for i in range(time_split):
@@ -37,7 +41,7 @@ def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c, time_widt
return x, x_dot, y, y_dot
- def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
+ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
if self.ref_footsteps is None:
print("No footsteps")
return
@@ -46,14 +50,11 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
if plot:
fig = plt.figure()
ax = Axes3D(fig)
+ fig.add_axes(ax)
com_trajectory_for_plot = []
- self.com_trajectory = []
- self.ref_p = [] # reference footstep positions
- self.act_p = [] # actual footstep positions
-
- px, py = 0.0, 0.0 # reference footstep position
- px_star, py_star = px, py # modified footstep position
+ px, py = 0.0, 0.0 # reference footstep position
+ px_star, py_star = px, py # modified footstep position
xi, xi_dot, yi, yi_dot = 0.0, 0.0, 0.01, 0.0
time = 0.0
n = 0
@@ -62,10 +63,10 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
for i in range(len(self.ref_footsteps)):
# simulate x, y and those of dot of inverted pendulum
xi, xi_dot, yi, yi_dot = self.inverted_pendulum(
- xi, xi_dot, px_star, yi, yi_dot, py_star, z_c, T_sup)
+ xi, xi_dot, px_star, yi, yi_dot, py_star, z_c, t_sup)
# update time
- time += T_sup
+ time += t_sup
n += 1
# calculate px, py, x_, y_, vx_, vy_
@@ -77,19 +78,22 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
f_x_next, f_y_next, f_theta_next = 0., 0., 0.
else:
f_x_next, f_y_next, f_theta_next = self.ref_footsteps[n]
- rotate_mat_next = np.array([[math.cos(f_theta_next), -math.sin(f_theta_next)],
- [math.sin(f_theta_next), math.cos(f_theta_next)]])
-
- T_c = math.sqrt(z_c / self.g)
- C = math.cosh(T_sup / T_c)
- S = math.sinh(T_sup / T_c)
-
- px, py = list(np.array(
- [px, py]) + np.dot(rotate_mat, np.array([f_x, -1 * math.pow(-1, n) * f_y])))
+ rotate_mat_next = np.array(
+ [[math.cos(f_theta_next), -math.sin(f_theta_next)],
+ [math.sin(f_theta_next), math.cos(f_theta_next)]])
+
+ Tc = math.sqrt(z_c / self.g)
+ C = math.cosh(t_sup / Tc)
+ S = math.sinh(t_sup / Tc)
+
+ px, py = list(np.array([px, py])
+ + np.dot(rotate_mat,
+ np.array([f_x, -1 * math.pow(-1, n) * f_y])
+ ))
x_, y_ = list(np.dot(rotate_mat_next, np.array(
[f_x_next / 2., math.pow(-1, n) * f_y_next / 2.])))
vx_, vy_ = list(np.dot(rotate_mat_next, np.array(
- [(1 + C) / (T_c * S) * x_, (C - 1) / (T_c * S) * y_])))
+ [(1 + C) / (Tc * S) * x_, (C - 1) / (Tc * S) * y_])))
self.ref_p.append([px, py, f_theta])
# calculate reference COM
@@ -97,67 +101,97 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
yd, yd_dot = py + y_, vy_
# calculate modified footsteps
- D = a * math.pow(C - 1, 2) + b * math.pow(S / T_c, 2)
- px_star = -a * (C - 1) / D * (xd - C * xi - T_c * S * xi_dot) - \
- b * S / (T_c * D) * (xd_dot - S / T_c * xi - C * xi_dot)
- py_star = -a * (C - 1) / D * (yd - C * yi - T_c * S * yi_dot) - \
- b * S / (T_c * D) * (yd_dot - S / T_c * yi - C * yi_dot)
+ D = a * math.pow(C - 1, 2) + b * math.pow(S / Tc, 2)
+ px_star = -a * (C - 1) / D * (xd - C * xi - Tc * S * xi_dot) \
+ - b * S / (Tc * D) * (xd_dot - S / Tc * xi - C * xi_dot)
+ py_star = -a * (C - 1) / D * (yd - C * yi - Tc * S * yi_dot) \
+ - b * S / (Tc * D) * (yd_dot - S / Tc * yi - C * yi_dot)
self.act_p.append([px_star, py_star, f_theta])
# plot
if plot:
- # for plot trajectory, plot in for loop
- for c in range(len(self.com_trajectory)):
- if c > len(com_trajectory_for_plot):
- # set up plotter
- plt.cla()
- ax.set_zlim(0, z_c * 2)
- ax.set_aspect('equal', 'datalim')
-
- # update com_trajectory_for_plot
- com_trajectory_for_plot.append(self.com_trajectory[c])
-
- # plot com
- ax.plot([p[0] for p in com_trajectory_for_plot], [p[1] for p in com_trajectory_for_plot], [
- 0 for p in com_trajectory_for_plot], color="red")
-
- # plot inverted pendulum
- ax.plot([px_star, com_trajectory_for_plot[-1][0]],
- [py_star, com_trajectory_for_plot[-1][1]],
- [0, z_c], color="green", linewidth=3)
- ax.scatter([com_trajectory_for_plot[-1][0]],
- [com_trajectory_for_plot[-1][1]],
- [z_c], color="green", s=300)
-
- # foot rectangle for self.ref_p
- foot_width = 0.06
- foot_height = 0.04
- for j in range(len(self.ref_p)):
- angle = self.ref_p[j][2] + \
- math.atan2(foot_height, foot_width) - math.pi
- r = math.sqrt(
- math.pow(foot_width / 3., 2) + math.pow(foot_height / 2., 2))
- rec = pat.Rectangle(xy=(self.ref_p[j][0] + r * math.cos(angle), self.ref_p[j][1] + r * math.sin(angle)),
- width=foot_width, height=foot_height, angle=self.ref_p[j][2] * 180 / math.pi, color="blue", fill=False, ls=":")
- ax.add_patch(rec)
- art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z")
-
- # foot rectangle for self.act_p
- for j in range(len(self.act_p)):
- angle = self.act_p[j][2] + \
- math.atan2(foot_height, foot_width) - math.pi
- r = math.sqrt(
- math.pow(foot_width / 3., 2) + math.pow(foot_height / 2., 2))
- rec = pat.Rectangle(xy=(self.act_p[j][0] + r * math.cos(angle), self.act_p[j][1] + r * math.sin(angle)),
- width=foot_width, height=foot_height, angle=self.act_p[j][2] * 180 / math.pi, color="blue", fill=False)
- ax.add_patch(rec)
- art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z")
-
- plt.draw()
- plt.pause(0.001)
+ self.plot_animation(ax, com_trajectory_for_plot, px_star,
+ py_star, z_c)
if plot:
plt.show()
+ def plot_animation(self, ax, com_trajectory_for_plot, px_star, py_star,
+ z_c): # pragma: no cover
+ # for plot trajectory, plot in for loop
+ for c in range(len(self.com_trajectory)):
+ if c > len(com_trajectory_for_plot):
+ # set up plotter
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event:
+ [exit(0) if event.key == 'escape' else None])
+ ax.set_zlim(0, z_c * 2)
+ ax.set_xlim(0, 1)
+ ax.set_ylim(-0.5, 0.5)
+
+ # update com_trajectory_for_plot
+ com_trajectory_for_plot.append(self.com_trajectory[c])
+
+ # plot com
+ ax.plot([p[0] for p in com_trajectory_for_plot],
+ [p[1] for p in com_trajectory_for_plot], [
+ 0 for _ in com_trajectory_for_plot],
+ color="red")
+
+ # plot inverted pendulum
+ ax.plot([px_star, com_trajectory_for_plot[-1][0]],
+ [py_star, com_trajectory_for_plot[-1][1]],
+ [0, z_c], color="green", linewidth=3)
+ ax.scatter([com_trajectory_for_plot[-1][0]],
+ [com_trajectory_for_plot[-1][1]],
+ [z_c], color="green", s=300)
+
+ # foot rectangle for self.ref_p
+ foot_width = 0.06
+ foot_height = 0.04
+ for j in range(len(self.ref_p)):
+ angle = self.ref_p[j][2] + \
+ math.atan2(foot_height,
+ foot_width) - math.pi
+ r = math.sqrt(
+ math.pow(foot_width / 3., 2) + math.pow(
+ foot_height / 2., 2))
+ rec = pat.Rectangle(xy=(
+ self.ref_p[j][0] + r * math.cos(angle),
+ self.ref_p[j][1] + r * math.sin(angle)),
+ width=foot_width,
+ height=foot_height,
+ angle=self.ref_p[j][
+ 2] * 180 / math.pi,
+ color="blue", fill=False,
+ ls=":")
+ ax.add_patch(rec)
+ art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z")
+
+ # foot rectangle for self.act_p
+ for j in range(len(self.act_p)):
+ angle = self.act_p[j][2] + \
+ math.atan2(foot_height,
+ foot_width) - math.pi
+ r = math.sqrt(
+ math.pow(foot_width / 3., 2) + math.pow(
+ foot_height / 2., 2))
+ rec = pat.Rectangle(xy=(
+ self.act_p[j][0] + r * math.cos(angle),
+ self.act_p[j][1] + r * math.sin(angle)),
+ width=foot_width,
+ height=foot_height,
+ angle=self.act_p[j][
+ 2] * 180 / math.pi,
+ color="blue", fill=False)
+ ax.add_patch(rec)
+ art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z")
+
+ plt.draw()
+ plt.pause(0.001)
+
if __name__ == "__main__":
bipedal_planner = BipedalPlanner()
diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md
new file mode 100644
index 0000000000..e8c4702596
--- /dev/null
+++ b/CODE_OF_CONDUCT.md
@@ -0,0 +1,76 @@
+# Contributor Covenant Code of Conduct
+
+## Our Pledge
+
+In the interest of fostering an open and welcoming environment, we as
+contributors and maintainers pledge to making participation in our project and
+our community a harassment-free experience for everyone, regardless of age, body
+size, disability, ethnicity, sex characteristics, gender identity and expression,
+level of experience, education, socio-economic status, nationality, personal
+appearance, race, religion, or sexual identity and orientation.
+
+## Our Standards
+
+Examples of behavior that contributes to creating a positive environment
+include:
+
+* Using welcoming and inclusive language
+* Being respectful of differing viewpoints and experiences
+* Gracefully accepting constructive criticism
+* Focusing on what is best for the community
+* Showing empathy towards other community members
+
+Examples of unacceptable behavior by participants include:
+
+* The use of sexualized language or imagery and unwelcome sexual attention or
+ advances
+* Trolling, insulting/derogatory comments, and personal or political attacks
+* Public or private harassment
+* Publishing others' private information, such as a physical or electronic
+ address, without explicit permission
+* Other conduct which could reasonably be considered inappropriate in a
+ professional setting
+
+## Our Responsibilities
+
+Project maintainers are responsible for clarifying the standards of acceptable
+behavior and are expected to take appropriate and fair corrective action in
+response to any instances of unacceptable behavior.
+
+Project maintainers have the right and responsibility to remove, edit, or
+reject comments, commits, code, wiki edits, issues, and other contributions
+that are not aligned to this Code of Conduct, or to ban temporarily or
+permanently any contributor for other behaviors that they deem inappropriate,
+threatening, offensive, or harmful.
+
+## Scope
+
+This Code of Conduct applies both within project spaces and in public spaces
+when an individual is representing the project or its community. Examples of
+representing a project or community include using an official project e-mail
+address, posting via an official social media account, or acting as an appointed
+representative at an online or offline event. Representation of a project may be
+further defined and clarified by project maintainers.
+
+## Enforcement
+
+Instances of abusive, harassing, or otherwise unacceptable behavior may be
+reported by contacting the project team at asakaig@gmail.com. All
+complaints will be reviewed and investigated and will result in a response that
+is deemed necessary and appropriate to the circumstances. The project team is
+obligated to maintain confidentiality with regard to the reporter of an incident.
+Further details of specific enforcement policies may be posted separately.
+
+Project maintainers who do not follow or enforce the Code of Conduct in good
+faith may face temporary or permanent repercussions as determined by other
+members of the project's leadership.
+
+## Attribution
+
+This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4,
+available at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html
+
+[homepage]: https://www.contributor-covenant.org
+
+For answers to common questions about this code of conduct, see
+https://www.contributor-covenant.org/faq
diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md
index fd41946b65..3bcc499e6a 100644
--- a/CONTRIBUTING.md
+++ b/CONTRIBUTING.md
@@ -1,23 +1,5 @@
-# Contributing to Python
+# Contributing
-:+1::tada: First of off, thanks very much for taking the time to contribute! :tada::+1:
+:+1::tada: First of all, thank you very much for taking the time to contribute! :tada::+1:
-The following is a set of guidelines for contributing to PythonRobotics.
-
-These are mostly guidelines, not rules.
-
-Use your best judgment, and feel free to propose changes to this document in a pull request.
-
-# Before contributing
-
-## Taking a look at the paper.
-
-Please check this paper to understand the philosophy of this project.
-
-- [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib))
-
-## Check your Python version.
-
-We only accept a PR for Python 3.6.x or higher.
-
-We will not accept a PR for Python 2.x.
+Please check this document for contribution: [How to contribute — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/0_getting_started/3_how_to_contribute.html)
diff --git a/Introduction/introduction.ipynb b/Introduction/introduction.ipynb
deleted file mode 100644
index c2fcc709a5..0000000000
--- a/Introduction/introduction.ipynb
+++ /dev/null
@@ -1,44 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "# Introduction"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": []
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Ref"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.7"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/InvertedPendulum/inverted_pendulum_lqr_control.py b/InvertedPendulum/inverted_pendulum_lqr_control.py
new file mode 100644
index 0000000000..c4380530b8
--- /dev/null
+++ b/InvertedPendulum/inverted_pendulum_lqr_control.py
@@ -0,0 +1,192 @@
+"""
+Inverted Pendulum LQR control
+author: Trung Kien - letrungkien.k53.hut@gmail.com
+"""
+
+import math
+import time
+
+import matplotlib.pyplot as plt
+import numpy as np
+from numpy.linalg import inv, eig
+
+# Model parameters
+
+l_bar = 2.0 # length of bar
+M = 1.0 # [kg]
+m = 0.3 # [kg]
+g = 9.8 # [m/s^2]
+
+nx = 4 # number of state
+nu = 1 # number of input
+Q = np.diag([0.0, 1.0, 1.0, 0.0]) # state cost matrix
+R = np.diag([0.01]) # input cost matrix
+
+delta_t = 0.1 # time tick [s]
+sim_time = 5.0 # simulation time [s]
+
+show_animation = True
+
+
+def main():
+ x0 = np.array([
+ [0.0],
+ [0.0],
+ [0.3],
+ [0.0]
+ ])
+
+ x = np.copy(x0)
+ time = 0.0
+
+ while sim_time > time:
+ time += delta_t
+
+ # calc control input
+ u = lqr_control(x)
+
+ # simulate inverted pendulum cart
+ x = simulation(x, u)
+
+ if show_animation:
+ plt.clf()
+ px = float(x[0, 0])
+ theta = float(x[2, 0])
+ plot_cart(px, theta)
+ plt.xlim([-5.0, 2.0])
+ plt.pause(0.001)
+
+ print("Finish")
+ print(f"x={float(x[0, 0]):.2f} [m] , theta={math.degrees(x[2, 0]):.2f} [deg]")
+ if show_animation:
+ plt.show()
+
+
+def simulation(x, u):
+ A, B = get_model_matrix()
+ x = A @ x + B @ u
+
+ return x
+
+
+def solve_DARE(A, B, Q, R, maxiter=150, eps=0.01):
+ """
+ Solve a discrete time_Algebraic Riccati equation (DARE)
+ """
+ P = Q
+
+ for i in range(maxiter):
+ Pn = A.T @ P @ A - A.T @ P @ B @ \
+ inv(R + B.T @ P @ B) @ B.T @ P @ A + Q
+ if (abs(Pn - P)).max() < eps:
+ break
+ P = Pn
+
+ return Pn
+
+
+def dlqr(A, B, Q, R):
+ """
+ Solve the discrete time lqr controller.
+ x[k+1] = A x[k] + B u[k]
+ cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k]
+ # ref Bertsekas, p.151
+ """
+
+ # first, try to solve the ricatti equation
+ P = solve_DARE(A, B, Q, R)
+
+ # compute the LQR gain
+ K = inv(B.T @ P @ B + R) @ (B.T @ P @ A)
+
+ eigVals, eigVecs = eig(A - B @ K)
+ return K, P, eigVals
+
+
+def lqr_control(x):
+ A, B = get_model_matrix()
+ start = time.time()
+ K, _, _ = dlqr(A, B, Q, R)
+ u = -K @ x
+ elapsed_time = time.time() - start
+ print(f"calc time:{elapsed_time:.6f} [sec]")
+ return u
+
+
+def get_numpy_array_from_matrix(x):
+ """
+ get build-in list from matrix
+ """
+ return np.array(x).flatten()
+
+
+def get_model_matrix():
+ A = np.array([
+ [0.0, 1.0, 0.0, 0.0],
+ [0.0, 0.0, m * g / M, 0.0],
+ [0.0, 0.0, 0.0, 1.0],
+ [0.0, 0.0, g * (M + m) / (l_bar * M), 0.0]
+ ])
+ A = np.eye(nx) + delta_t * A
+
+ B = np.array([
+ [0.0],
+ [1.0 / M],
+ [0.0],
+ [1.0 / (l_bar * M)]
+ ])
+ B = delta_t * B
+
+ return A, B
+
+
+def flatten(a):
+ return np.array(a).flatten()
+
+
+def plot_cart(xt, theta):
+ cart_w = 1.0
+ cart_h = 0.5
+ radius = 0.1
+
+ cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w /
+ 2.0, -cart_w / 2.0, -cart_w / 2.0])
+ cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0])
+ cy += radius * 2.0
+
+ cx = cx + xt
+
+ bx = np.array([0.0, l_bar * math.sin(-theta)])
+ bx += xt
+ by = np.array([cart_h, l_bar * math.cos(-theta) + cart_h])
+ by += radius * 2.0
+
+ angles = np.arange(0.0, math.pi * 2.0, math.radians(3.0))
+ ox = np.array([radius * math.cos(a) for a in angles])
+ oy = np.array([radius * math.sin(a) for a in angles])
+
+ rwx = np.copy(ox) + cart_w / 4.0 + xt
+ rwy = np.copy(oy) + radius
+ lwx = np.copy(ox) - cart_w / 4.0 + xt
+ lwy = np.copy(oy) + radius
+
+ wx = np.copy(ox) + bx[-1]
+ wy = np.copy(oy) + by[-1]
+
+ plt.plot(flatten(cx), flatten(cy), "-b")
+ plt.plot(flatten(bx), flatten(by), "-k")
+ plt.plot(flatten(rwx), flatten(rwy), "-k")
+ plt.plot(flatten(lwx), flatten(lwy), "-k")
+ plt.plot(flatten(wx), flatten(wy), "-k")
+ plt.title(f"x: {xt:.2f} , theta: {math.degrees(theta):.2f}")
+
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
+ plt.axis("equal")
+
+
+if __name__ == '__main__':
+ main()
diff --git a/InvertedPendulum/inverted_pendulum_mpc_control.py b/InvertedPendulum/inverted_pendulum_mpc_control.py
new file mode 100644
index 0000000000..c45dde8acc
--- /dev/null
+++ b/InvertedPendulum/inverted_pendulum_mpc_control.py
@@ -0,0 +1,187 @@
+"""
+Inverted Pendulum MPC control
+author: Atsushi Sakai
+"""
+
+import math
+import time
+
+import cvxpy
+import matplotlib.pyplot as plt
+import numpy as np
+
+# Model parameters
+
+l_bar = 2.0 # length of bar
+M = 1.0 # [kg]
+m = 0.3 # [kg]
+g = 9.8 # [m/s^2]
+
+nx = 4 # number of state
+nu = 1 # number of input
+Q = np.diag([0.0, 1.0, 1.0, 0.0]) # state cost matrix
+R = np.diag([0.01]) # input cost matrix
+
+T = 30 # Horizon length
+delta_t = 0.1 # time tick
+sim_time = 5.0 # simulation time [s]
+
+show_animation = True
+
+
+def main():
+ x0 = np.array([
+ [0.0],
+ [0.0],
+ [0.3],
+ [0.0]
+ ])
+
+ x = np.copy(x0)
+ time = 0.0
+
+ while sim_time > time:
+ time += delta_t
+
+ # calc control input
+ opt_x, opt_delta_x, opt_theta, opt_delta_theta, opt_input = \
+ mpc_control(x)
+
+ # get input
+ u = opt_input[0]
+
+ # simulate inverted pendulum cart
+ x = simulation(x, u)
+
+ if show_animation:
+ plt.clf()
+ px = float(x[0, 0])
+ theta = float(x[2, 0])
+ plot_cart(px, theta)
+ plt.xlim([-5.0, 2.0])
+ plt.pause(0.001)
+
+ print("Finish")
+ print(f"x={float(x[0, 0]):.2f} [m] , theta={math.degrees(x[2, 0]):.2f} [deg]")
+ if show_animation:
+ plt.show()
+
+
+def simulation(x, u):
+ A, B = get_model_matrix()
+ x = np.dot(A, x) + np.dot(B, u)
+
+ return x
+
+
+def mpc_control(x0):
+ x = cvxpy.Variable((nx, T + 1))
+ u = cvxpy.Variable((nu, T))
+
+ A, B = get_model_matrix()
+
+ cost = 0.0
+ constr = []
+ for t in range(T):
+ cost += cvxpy.quad_form(x[:, t + 1], Q)
+ cost += cvxpy.quad_form(u[:, t], R)
+ constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t]]
+
+ constr += [x[:, 0] == x0[:, 0]]
+ prob = cvxpy.Problem(cvxpy.Minimize(cost), constr)
+
+ start = time.time()
+ prob.solve(verbose=False, solver=cvxpy.CLARABEL)
+ elapsed_time = time.time() - start
+ print(f"calc time:{elapsed_time:.6f} [sec]")
+
+ if prob.status == cvxpy.OPTIMAL:
+ ox = get_numpy_array_from_matrix(x.value[0, :])
+ dx = get_numpy_array_from_matrix(x.value[1, :])
+ theta = get_numpy_array_from_matrix(x.value[2, :])
+ d_theta = get_numpy_array_from_matrix(x.value[3, :])
+
+ ou = get_numpy_array_from_matrix(u.value[0, :])
+ else:
+ ox, dx, theta, d_theta, ou = None, None, None, None, None
+
+ return ox, dx, theta, d_theta, ou
+
+
+def get_numpy_array_from_matrix(x):
+ """
+ get build-in list from matrix
+ """
+ return np.array(x).flatten()
+
+
+def get_model_matrix():
+ A = np.array([
+ [0.0, 1.0, 0.0, 0.0],
+ [0.0, 0.0, m * g / M, 0.0],
+ [0.0, 0.0, 0.0, 1.0],
+ [0.0, 0.0, g * (M + m) / (l_bar * M), 0.0]
+ ])
+ A = np.eye(nx) + delta_t * A
+
+ B = np.array([
+ [0.0],
+ [1.0 / M],
+ [0.0],
+ [1.0 / (l_bar * M)]
+ ])
+ B = delta_t * B
+
+ return A, B
+
+
+def flatten(a):
+ return np.array(a).flatten()
+
+
+def plot_cart(xt, theta):
+ cart_w = 1.0
+ cart_h = 0.5
+ radius = 0.1
+
+ cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w /
+ 2.0, -cart_w / 2.0, -cart_w / 2.0])
+ cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0])
+ cy += radius * 2.0
+
+ cx = cx + xt
+
+ bx = np.array([0.0, l_bar * math.sin(-theta)])
+ bx += xt
+ by = np.array([cart_h, l_bar * math.cos(-theta) + cart_h])
+ by += radius * 2.0
+
+ angles = np.arange(0.0, math.pi * 2.0, math.radians(3.0))
+ ox = np.array([radius * math.cos(a) for a in angles])
+ oy = np.array([radius * math.sin(a) for a in angles])
+
+ rwx = np.copy(ox) + cart_w / 4.0 + xt
+ rwy = np.copy(oy) + radius
+ lwx = np.copy(ox) - cart_w / 4.0 + xt
+ lwy = np.copy(oy) + radius
+
+ wx = np.copy(ox) + bx[-1]
+ wy = np.copy(oy) + by[-1]
+
+ plt.plot(flatten(cx), flatten(cy), "-b")
+ plt.plot(flatten(bx), flatten(by), "-k")
+ plt.plot(flatten(rwx), flatten(rwy), "-k")
+ plt.plot(flatten(lwx), flatten(lwy), "-k")
+ plt.plot(flatten(wx), flatten(wy), "-k")
+ plt.title(f"x: {xt:.2f} , theta: {math.degrees(theta):.2f}")
+
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
+ plt.axis("equal")
+
+
+if __name__ == '__main__':
+ main()
diff --git a/LICENSE b/LICENSE
index 9d60d1828f..1c9b928b54 100644
--- a/LICENSE
+++ b/LICENSE
@@ -1,6 +1,7 @@
The MIT License (MIT)
-Copyright (c) 2016 Atsushi Sakai
+Copyright (c) 2016 - now Atsushi Sakai and other contributors:
+https://github.com/AtsushiSakai/PythonRobotics/contributors
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
diff --git a/Localization/Kalmanfilter_basics.ipynb b/Localization/Kalmanfilter_basics.ipynb
deleted file mode 100644
index 374287911b..0000000000
--- a/Localization/Kalmanfilter_basics.ipynb
+++ /dev/null
@@ -1,762 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## KF Basics - Part I\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Introduction\n",
- "#### What is the need to describe belief in terms of PDF's?\n",
- "This is because robot environments are stochastic. A robot environment may have cows with Tesla by side. That is a robot and it's environment cannot be deterministically modelled(e.g as a function of something like time t). In the real world sensors are also error prone, and hence there'll be a set of values with a mean and variance that it can take. Hence, we always have to model around some mean and variances associated."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### What is Expectation of a Random Variables?\n",
- " Expectation is nothing but an average of the probabilites\n",
- " \n",
- "$$\\mathbb E[X] = \\sum_{i=1}^n p_ix_i$$\n",
- "\n",
- "In the continous form,\n",
- "\n",
- "$$\\mathbb E[X] = \\int_{-\\infty}^\\infty x\\, f(x) \\,dx$$\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "1.4000000000000001\n"
- ]
- }
- ],
- "source": [
- "import numpy as np\n",
- "import random\n",
- "x=[3,1,2]\n",
- "p=[0.1,0.3,0.4]\n",
- "E_x=np.sum(np.multiply(x,p))\n",
- "print(E_x)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### What is the advantage of representing the belief as a unimodal as opposed to multimodal?\n",
- "Obviously, it makes sense because we can't multiple probabilities to a car moving for two locations. This would be too confusing and the information will not be useful."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": null,
- "metadata": {},
- "outputs": [],
- "source": []
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Variance, Covariance and Correlation\n",
- "\n",
- "#### Variance\n",
- "Variance is the spread of the data. The mean does'nt tell much **about** the data. Therefore the variance tells us about the **story** about the data meaning the spread of the data.\n",
- "\n",
- "$$\\mathit{VAR}(X) = \\frac{1}{n}\\sum_{i=1}^n (x_i - \\mu)^2$$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "1.0224618077401504"
- ]
- },
- "execution_count": 3,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "x=np.random.randn(10)\n",
- "np.var(x)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### Covariance\n",
- "\n",
- "This is for a multivariate distribution. For example, a robot in 2-D space can take values in both x and y. To describe them, a normal distribution with mean in both x and y is needed.\n",
- "\n",
- "For a multivariate distribution, mean $\\mu$ can be represented as a matrix, \n",
- "\n",
- "$$\n",
- "\\mu = \\begin{bmatrix}\\mu_1\\\\\\mu_2\\\\ \\vdots \\\\\\mu_n\\end{bmatrix}\n",
- "$$\n",
- "\n",
- "\n",
- "Similarly, variance can also be represented.\n",
- "\n",
- "But an important concept is that in the same way as every variable or dimension has a variation in its values, it is also possible that there will be values on how they **together vary**. This is also a measure of how two datasets are related to each other or **correlation**.\n",
- "\n",
- "For example, as height increases weight also generally increases. These variables are correlated. They are positively correlated because as one variable gets larger so does the other.\n",
- "\n",
- "We use a **covariance matrix** to denote covariances of a multivariate normal distribution:\n",
- "$$\n",
- "\\Sigma = \\begin{bmatrix}\n",
- " \\sigma_1^2 & \\sigma_{12} & \\cdots & \\sigma_{1n} \\\\\n",
- " \\sigma_{21} &\\sigma_2^2 & \\cdots & \\sigma_{2n} \\\\\n",
- " \\vdots & \\vdots & \\ddots & \\vdots \\\\\n",
- " \\sigma_{n1} & \\sigma_{n2} & \\cdots & \\sigma_n^2\n",
- " \\end{bmatrix}\n",
- "$$\n",
- "\n",
- "**Diagonal** - Variance of each variable associated. \n",
- "\n",
- "**Off-Diagonal** - covariance between ith and jth variables.\n",
- "\n",
- "$$\\begin{aligned}VAR(X) = \\sigma_x^2 &= \\frac{1}{n}\\sum_{i=1}^n(X - \\mu)^2\\\\\n",
- "COV(X, Y) = \\sigma_{xy} &= \\frac{1}{n}\\sum_{i=1}^n[(X-\\mu_x)(Y-\\mu_y)\\big]\\end{aligned}$$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 4,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([[0.08868895, 0.05064471, 0.08855629],\n",
- " [0.05064471, 0.06219243, 0.11555291],\n",
- " [0.08855629, 0.11555291, 0.21534324]])"
- ]
- },
- "execution_count": 4,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "x=np.random.random((3,3))\n",
- "np.cov(x)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Covariance taking the data as **sample** with $\\frac{1}{N-1}$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 17,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([[ 0.1571437 , -0.00766623],\n",
- " [-0.00766623, 0.13957621]])"
- ]
- },
- "execution_count": 17,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "x_cor=np.random.rand(1,10)\n",
- "y_cor=np.random.rand(1,10)\n",
- "np.cov(x_cor,y_cor)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Covariance taking the data as **population** with $\\frac{1}{N}$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 18,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([[ 0.14142933, -0.0068996 ],\n",
- " [-0.0068996 , 0.12561859]])"
- ]
- },
- "execution_count": 18,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "np.cov(x_cor,y_cor,bias=1)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Gaussians \n",
- "\n",
- "#### Central Limit Theorem\n",
- "\n",
- "According to this theorem, the average of n samples of random and independant variables tends to follow a normal distribution as we increase the sample size.(Generally, for n>=30)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "(array([ 1., 4., 9., 12., 12., 20., 16., 16., 4., 6.]),\n",
- " array([5.30943011, 5.34638597, 5.38334183, 5.42029769, 5.45725355,\n",
- " 5.49420941, 5.53116527, 5.56812114, 5.605077 , 5.64203286,\n",
- " 5.67898872]),\n",
- " )"
- ]
- },
- "execution_count": 5,
- "metadata": {},
- "output_type": "execute_result"
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "import matplotlib.pyplot as plt\n",
- "import random\n",
- "a=np.zeros((100,))\n",
- "for i in range(100):\n",
- " x=[random.uniform(1,10) for _ in range(1000)]\n",
- " a[i]=np.sum(x,axis=0)/1000\n",
- "plt.hist(a)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": null,
- "metadata": {},
- "outputs": [],
- "source": []
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### Gaussian Distribution\n",
- "A Gaussian is a *continuous probability distribution* that is completely described with two parameters, the mean ($\\mu$) and the variance ($\\sigma^2$). It is defined as:\n",
- "\n",
- "$$ \n",
- "f(x, \\mu, \\sigma) = \\frac{1}{\\sigma\\sqrt{2\\pi}} \\exp\\big [{-\\frac{(x-\\mu)^2}{2\\sigma^2} }\\big ]\n",
- "$$\n",
- "Range is $$[-\\inf,\\inf] $$\n",
- "\n",
- "\n",
- "This is just a function of mean($\\mu$) and standard deviation ($\\sigma$) and what gives the normal distribution the charecteristic **bell curve**. "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 7,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "import matplotlib.mlab as mlab\n",
- "import math\n",
- "import scipy.stats\n",
- "\n",
- "mu = 0\n",
- "variance = 5\n",
- "sigma = math.sqrt(variance)\n",
- "x = np.linspace(mu - 5*sigma, mu + 5*sigma, 100)\n",
- "plt.plot(x,scipy.stats.norm.pdf(x, mu, sigma))\n",
- "plt.show()\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": null,
- "metadata": {},
- "outputs": [],
- "source": []
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### Why do we need Gaussian distributions?\n",
- "Since it becomes really difficult in the real world to deal with multimodal distribution as we cannot put the belief in two seperate location of the robots. This becomes really confusing and in practice impossible to comprehend. \n",
- "Gaussian probability distribution allows us to drive the robots using only one mode with peak at the mean with some variance."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Gaussian Properties\n",
- "\n",
- "**Multiplication**\n",
- "\n",
- "\n",
- "For the measurement update in a Bayes Filter, the algorithm tells us to multiply the Prior P(X_t) and measurement P(Z_t|X_t) to calculate the posterior:\n",
- "\n",
- "$$P(X \\mid Z) = \\frac{P(Z \\mid X)P(X)}{P(Z)}$$\n",
- "\n",
- "Here for the numerator, $P(Z \\mid X),P(X)$ both are gaussian.\n",
- "\n",
- "$N(\\bar\\mu, \\bar\\sigma^1)$ and $N(\\bar\\mu, \\bar\\sigma^2)$ are their mean and variances.\n",
- "\n",
- "New mean is \n",
- "\n",
- "$$\\mu_\\mathtt{new} = \\frac{\\sigma_z^2\\bar\\mu + \\bar\\sigma^2z}{\\bar\\sigma^2+\\sigma_z^2}$$\n",
- "New variance is\n",
- "$$\n",
- "\\sigma_\\mathtt{new} = \\frac{\\sigma_z^2\\bar\\sigma^2}{\\bar\\sigma^2+\\sigma_z^2}\n",
- "$$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 9,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "New mean is at: 5.0\n",
- "New variance is: 1.0\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "import matplotlib.mlab as mlab\n",
- "import math\n",
- "mu1 = 0\n",
- "variance1 = 2\n",
- "sigma = math.sqrt(variance1)\n",
- "x1 = np.linspace(mu1 - 3*sigma, mu1 + 3*sigma, 100)\n",
- "plt.plot(x1,scipy.stats.norm.pdf(x1, mu1, sigma),label='prior')\n",
- "\n",
- "mu2 = 10\n",
- "variance2 = 2\n",
- "sigma = math.sqrt(variance2)\n",
- "x2 = np.linspace(mu2 - 3*sigma, mu2 + 3*sigma, 100)\n",
- "plt.plot(x2,scipy.stats.norm.pdf(x2, mu2, sigma),\"g-\",label='measurement')\n",
- "\n",
- "\n",
- "mu_new=(mu1*variance2+mu2*variance1)/(variance1+variance2)\n",
- "print(\"New mean is at: \",mu_new)\n",
- "var_new=(variance1*variance2)/(variance1+variance2)\n",
- "print(\"New variance is: \",var_new)\n",
- "sigma = math.sqrt(var_new)\n",
- "x3 = np.linspace(mu_new - 3*sigma, mu_new + 3*sigma, 100)\n",
- "plt.plot(x3,scipy.stats.norm.pdf(x3, mu_new, var_new),label=\"posterior\")\n",
- "plt.legend(loc='upper left')\n",
- "plt.xlim(-10,20)\n",
- "plt.show()\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "**Addition**\n",
- "\n",
- "The motion step involves a case of adding up probability (Since it has to abide the Law of Total Probability). This means their beliefs are to be added and hence two gaussians. They are simply arithmetic additions of the two.\n",
- "\n",
- "$$\\begin{gathered}\\mu_x = \\mu_p + \\mu_z \\\\\n",
- "\\sigma_x^2 = \\sigma_z^2+\\sigma_p^2\\, \\square\\end{gathered}$$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 10,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "New mean is at: 15\n",
- "New variance is: 2\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "import matplotlib.mlab as mlab\n",
- "import math\n",
- "mu1 = 5\n",
- "variance1 = 1\n",
- "sigma = math.sqrt(variance1)\n",
- "x1 = np.linspace(mu1 - 3*sigma, mu1 + 3*sigma, 100)\n",
- "plt.plot(x1,scipy.stats.norm.pdf(x1, mu1, sigma),label='prior')\n",
- "\n",
- "mu2 = 10\n",
- "variance2 = 1\n",
- "sigma = math.sqrt(variance2)\n",
- "x2 = np.linspace(mu2 - 3*sigma, mu2 + 3*sigma, 100)\n",
- "plt.plot(x2,scipy.stats.norm.pdf(x2, mu2, sigma),\"g-\",label='measurement')\n",
- "\n",
- "\n",
- "mu_new=mu1+mu2\n",
- "print(\"New mean is at: \",mu_new)\n",
- "var_new=(variance1+variance2)\n",
- "print(\"New variance is: \",var_new)\n",
- "sigma = math.sqrt(var_new)\n",
- "x3 = np.linspace(mu_new - 3*sigma, mu_new + 3*sigma, 100)\n",
- "plt.plot(x3,scipy.stats.norm.pdf(x3, mu_new, var_new),label=\"posterior\")\n",
- "plt.legend(loc='upper left')\n",
- "plt.xlim(-10,20)\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 188,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "#Example from:\n",
- "#https://scipython.com/blog/visualizing-the-bivariate-gaussian-distribution/\n",
- "import numpy as np\n",
- "import matplotlib.pyplot as plt\n",
- "from matplotlib import cm\n",
- "from mpl_toolkits.mplot3d import Axes3D\n",
- "\n",
- "# Our 2-dimensional distribution will be over variables X and Y\n",
- "N = 60\n",
- "X = np.linspace(-3, 3, N)\n",
- "Y = np.linspace(-3, 4, N)\n",
- "X, Y = np.meshgrid(X, Y)\n",
- "\n",
- "# Mean vector and covariance matrix\n",
- "mu = np.array([0., 1.])\n",
- "Sigma = np.array([[ 1. , -0.5], [-0.5, 1.5]])\n",
- "\n",
- "# Pack X and Y into a single 3-dimensional array\n",
- "pos = np.empty(X.shape + (2,))\n",
- "pos[:, :, 0] = X\n",
- "pos[:, :, 1] = Y\n",
- "\n",
- "def multivariate_gaussian(pos, mu, Sigma):\n",
- " \"\"\"Return the multivariate Gaussian distribution on array pos.\n",
- "\n",
- " pos is an array constructed by packing the meshed arrays of variables\n",
- " x_1, x_2, x_3, ..., x_k into its _last_ dimension.\n",
- "\n",
- " \"\"\"\n",
- "\n",
- " n = mu.shape[0]\n",
- " Sigma_det = np.linalg.det(Sigma)\n",
- " Sigma_inv = np.linalg.inv(Sigma)\n",
- " N = np.sqrt((2*np.pi)**n * Sigma_det)\n",
- " # This einsum call calculates (x-mu)T.Sigma-1.(x-mu) in a vectorized\n",
- " # way across all the input variables.\n",
- " fac = np.einsum('...k,kl,...l->...', pos-mu, Sigma_inv, pos-mu)\n",
- "\n",
- " return np.exp(-fac / 2) / N\n",
- "\n",
- "# The distribution on the variables X, Y packed into pos.\n",
- "Z = multivariate_gaussian(pos, mu, Sigma)\n",
- "\n",
- "# Create a surface plot and projected filled contour plot under it.\n",
- "fig = plt.figure()\n",
- "ax = fig.gca(projection='3d')\n",
- "ax.plot_surface(X, Y, Z, rstride=3, cstride=3, linewidth=1, antialiased=True,\n",
- " cmap=cm.viridis)\n",
- "\n",
- "cset = ax.contourf(X, Y, Z, zdir='z', offset=-0.15, cmap=cm.viridis)\n",
- "\n",
- "# Adjust the limits, ticks and view angle\n",
- "ax.set_zlim(-0.15,0.2)\n",
- "ax.set_zticks(np.linspace(0,0.2,5))\n",
- "ax.view_init(27, -21)\n",
- "\n",
- "plt.show()\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "This is a 3D projection of the gaussians involved with the lower surface showing the 2D projection of the 3D projection above. The innermost ellipse represents the highest peak, that is the maximum probability for a given (X,Y) value.\n",
- "\n",
- "\n",
- "\n",
- "\n",
- "** numpy einsum examples **"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 175,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "[[ 0 1 2 3 4]\n",
- " [ 5 6 7 8 9]\n",
- " [10 11 12 13 14]\n",
- " [15 16 17 18 19]\n",
- " [20 21 22 23 24]]\n",
- "[0 1 2 3 4]\n",
- "[[0 1 2]\n",
- " [3 4 5]]\n"
- ]
- }
- ],
- "source": [
- "a = np.arange(25).reshape(5,5)\n",
- "b = np.arange(5)\n",
- "c = np.arange(6).reshape(2,3)\n",
- "print(a)\n",
- "print(b)\n",
- "print(c)\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 204,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([ 30, 80, 130, 180, 230])"
- ]
- },
- "execution_count": 204,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "#this is the diagonal sum, i repeated means the diagonal\n",
- "np.einsum('ij', a)\n",
- "#this takes the output ii which is the diagonal and outputs to a\n",
- "np.einsum('ii->i',a)\n",
- "#this takes in the array A represented by their axes 'ij' and B by its only axes'j' \n",
- "#and multiples them element wise\n",
- "np.einsum('ij,j',a, b)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 199,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([ 0, 22, 76])"
- ]
- },
- "execution_count": 199,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "A = np.arange(3).reshape(3,1)\n",
- "B = np.array([[ 0, 1, 2, 3],\n",
- " [ 4, 5, 6, 7],\n",
- " [ 8, 9, 10, 11]])\n",
- "C=np.multiply(A,B)\n",
- "np.sum(C,axis=1)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 197,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- "array([ 0, 22, 76])"
- ]
- },
- "execution_count": 197,
- "metadata": {},
- "output_type": "execute_result"
- }
- ],
- "source": [
- "D = np.array([0,1,2])\n",
- "E = np.array([[ 0, 1, 2, 3],\n",
- " [ 4, 5, 6, 7],\n",
- " [ 8, 9, 10, 11]])\n",
- "\n",
- "np.einsum('i,ij->i',D,E)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 238,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "text/plain": [
- ""
- ]
- },
- "execution_count": 238,
- "metadata": {},
- "output_type": "execute_result"
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "from scipy.stats import multivariate_normal\n",
- "x, y = np.mgrid[-5:5:.1, -5:5:.1]\n",
- "pos = np.empty(x.shape + (2,))\n",
- "pos[:, :, 0] = x; pos[:, :, 1] = y\n",
- "rv = multivariate_normal([0.5, -0.2], [[2.0, 0.9], [0.9, 0.5]])\n",
- "plt.contourf(x, y, rv.pdf(pos))\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": []
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### References:\n",
- "\n",
- "1. Roger Labbe's [repo](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python) on Kalman Filters. (Majority of the examples in the notes are from this)\n",
- "\n",
- "\n",
- "\n",
- "2. Probabilistic Robotics by Sebastian Thrun, Wolfram Burgard and Dieter Fox, MIT Press.\n",
- "\n",
- "\n",
- "\n",
- "3. Scipy [Documentation](https://scipython.com/blog/visualizing-the-bivariate-gaussian-distribution/)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": []
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.6"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/Localization/Kalmanfilter_basics_2.ipynb b/Localization/Kalmanfilter_basics_2.ipynb
deleted file mode 100644
index ac3101d518..0000000000
--- a/Localization/Kalmanfilter_basics_2.ipynb
+++ /dev/null
@@ -1,372 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## KF Basics - Part 2\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Probabilistic Generative Laws\n",
- " \n",
- "#### 1st Law:\n",
- "The belief representing the state $x_{t}$, is conditioned on all past states, measurements and controls. This can be shown mathematically by the conditional probability shown below:\n",
- "\n",
- "$$p(x_{t} | x_{0:t-1},z_{1:t-1},u_{1:t})$$\n",
- "\n",
- "1) $z_{t}$ represents the **measurement**\n",
- "\n",
- "2) $u_{t}$ the **motion command**\n",
- "\n",
- "3) $x_{t}$ the **state** (can be the position, velocity, etc) of the robot or its environment at time t.\n",
- "\n",
- "\n",
- "'If we know the state $x_{t-1}$ and $u_{t}$, then knowing the states $x_{0:t-2}$, $z_{1:t-1}$ becomes immaterial through the property of **conditional independence**'. The state $x_{t-1}$ introduces a conditional independence between $x_{t}$ and $z_{1:t-1}$, $u_{1:t-1}$\n",
- "\n",
- "Therefore the law now holds as:\n",
- "\n",
- "$$p(x_{t} | x_{0:t-1},z_{1:t-1},u_{1:t})=p(x_{t} | x_{t-1},u_{t})$$\n",
- "\n",
- "#### 2nd Law:\n",
- "\n",
- "If $x_{t}$ is complete, then:\n",
- "\n",
- "$$p(z_{t} | x-_{0:t},z_{1:t-1},u_{1:t})=p(z_{t} | x_{t})$$\n",
- "\n",
- "$x_{t}$ is **complete** means that the past states, controls or measurements carry no additional information to predict future.\n",
- "\n",
- "$x_{0:t-1}$, $z_{1:t-1}$ and $u_{1:t}$ are **conditionally independent** of $z_{t}$ given $x_{t}$ of complete.\n",
- "\n",
- "The filter works in two parts:\n",
- "\n",
- "$p(x_{t} | x_{t-1},u_{t})$ -> **State Transition Probability**\n",
- "\n",
- "$p(z_{t} | x_{t})$ -> **Measurement Probability**\n",
- "\n",
- "\n",
- "### Conditional dependence and independence example:\n",
- "\n",
- "\n",
- "$\\bullet$**Independent but conditionally dependent**\n",
- "\n",
- "Let's say you flip two fair coins\n",
- "\n",
- "A - Your first coin flip is heads\n",
- "\n",
- "B - Your second coin flip is heads\n",
- "\n",
- "C - Your first two flips were the same\n",
- "\n",
- "\n",
- "A and B here are independent. However, A and B are conditionally dependent given C, since if you know C then your first coin flip will inform the other one.\n",
- "\n",
- "$\\bullet$**Dependent but conditionally independent**\n",
- "\n",
- "A box contains two coins: a regular coin and one fake two-headed coin ((P(H)=1). I choose a coin at random and toss it twice. Define the following events.\n",
- "\n",
- "A= First coin toss results in an H.\n",
- "\n",
- "B= Second coin toss results in an H.\n",
- "\n",
- "C= Coin 1 (regular) has been selected. \n",
- "\n",
- "If we know A has occurred (i.e., the first coin toss has resulted in heads), we would guess that it is more likely that we have chosen Coin 2 than Coin 1. This in turn increases the conditional probability that B occurs. This suggests that A and B are not independent. On the other hand, given C (Coin 1 is selected), A and B are independent.\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Bayes Rule:\n",
- "\n",
- "\n",
- "Posterior = $$\\frac{Likelihood*Prior}{Marginal} $$\n",
- "\n",
- "Here,\n",
- "\n",
- "**Posterior** = Probability of an event occurring based on certain evidence.\n",
- "\n",
- "**Likelihood** = How probable is the evidence given the event.\n",
- "\n",
- "**Prior** = Probability of the just the event occurring without having any evidence.\n",
- "\n",
- "**Marginal** = Probability of the evidence given all the instances of events possible.\n",
- "\n",
- "\n",
- "\n",
- "Example:\n",
- "\n",
- "1% of women have breast cancer (and therefore 99% do not).\n",
- "80% of mammograms detect breast cancer when it is there (and therefore 20% miss it).\n",
- "9.6% of mammograms detect breast cancer when its not there (and therefore 90.4% correctly return a negative result).\n",
- "\n",
- "We can turn the process above into an equation, which is Bayes Theorem. Here is the equation:\n",
- "\n",
- "$\\displaystyle{\\Pr(\\mathrm{A}|\\mathrm{X}) = \\frac{\\Pr(\\mathrm{X}|\\mathrm{A})\\Pr(\\mathrm{A})}{\\Pr(\\mathrm{X|A})\\Pr(\\mathrm{A})+ \\Pr(\\mathrm{X | not \\ A})\\Pr(\\mathrm{not \\ A})}}$\n",
- "\n",
- "\n",
- "$\\bullet$Pr(A|X) = Chance of having cancer (A) given a positive test (X). This is what we want to know: How likely is it to have cancer with a positive result? In our case it was 7.8%.\n",
- "\n",
- "$\\bullet$Pr(X|A) = Chance of a positive test (X) given that you had cancer (A). This is the chance of a true positive, 80% in our case.\n",
- "\n",
- "$\\bullet$Pr(A) = Chance of having cancer (1%).\n",
- "\n",
- "$\\bullet$Pr(not A) = Chance of not having cancer (99%).\n",
- "\n",
- "$\\bullet$Pr(X|not A) = Chance of a positive test (X) given that you didn't have cancer (~A). This is a false positive, 9.6% in our case.\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Bayes Filter Algorithm\n",
- "\n",
- "The basic filter algorithm is:\n",
- "\n",
- "for all $x_{t}$:\n",
- "\n",
- "1. $\\overline{bel}(x_t) = \\int p(x_t | u_t, x_{t-1}) bel(x_{t-1})dx$\n",
- "\n",
- "2. $bel(x_t) = \\eta p(z_t | x_t) \\overline{bel}(x_t)$\n",
- "\n",
- "end.\n",
- "\n",
- "\n",
- "$\\rightarrow$The first step in filter is to calculate the prior for the next step that uses the bayes theorem. This is the **Prediction** step. The belief, $\\overline{bel}(x_t)$, is **before** incorporating measurement($z_{t}$) at time t=t. This is the step where the motion occurs and information is lost because the means and covariances of the gaussians are added. The RHS of the equation incorporates the law of total probability for prior calculation.\n",
- "\n",
- "$\\rightarrow$ This is the **Correction** or update step that calculates the belief of the robot **after** taking into account the measurement($z_{t}$) at time t=t. This is where we incorporate the sensor information for the whereabouts of the robot. We gain information here as the gaussians get multiplied here. (Multiplication of gaussian values allows the resultant to lie in between these numbers and the resultant covariance is smaller.\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Bayes filter localization example:"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 3,
- "metadata": {
- "image/png": {
- "width": 400
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"bayes_filter.png\",width=400)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\n",
- "Given - A robot with a sensor to detect doorways along a hallway. Also, the robot knows how the hallway looks like but doesn't know where it is in the map. \n",
- "\n",
- "\n",
- "1. Initially(first scenario), it doesn't know where it is with respect to the map and hence the belief assigns equal probability to each location in the map.\n",
- "\n",
- "\n",
- "2. The first sensor reading is incorporated and it shows the presence of a door. Now the robot knows how the map looks like but cannot localize yet as map has 3 doors present. Therefore it assigns equal probability to each door present. \n",
- "\n",
- "\n",
- "3. The robot now moves forward. This is the prediction step and the motion causes the robot to lose some of the information and hence the variance of the gaussians increase (diagram 4.). The final belief is **convolution** of posterior from previous step and the current state after motion. Also, the means shift on the right due to the motion.\n",
- "\n",
- "\n",
- "4. Again, incorporating the measurement, the sensor senses a door and this time too the possibility of door is equal for the three door. This is where the filter's magic kicks in. For the final belief (diagram 5.), the posterior calculated after sensing is mixed or **convolution** of previous posterior and measurement. It improves the robot's belief at location near to the second door. The variance **decreases** and **peaks**.\n",
- "\n",
- "\n",
- "5. Finally after series of iterations of motion and correction, the robot is able to localize itself with respect to the environment.(diagram 6.)\n",
- "\n",
- "Do note that the robot knows the map but doesn't know where exactly it is on the map."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Bayes and Kalman filter structure\n",
- "\n",
- "The basic structure and the concept remains the same as bayes filter for Kalman. The only key difference is the mathematical representation of Kalman filter. The Kalman filter is nothing but a bayesian filter that uses Gaussians.\n",
- "\n",
- "For a bayes filter to be a Kalman filter, **each term of belief is now a gaussian**, unlike histograms. The basic formulation for the **bayes filter** algorithm is:\n",
- "\n",
- "$$\\begin{aligned} \n",
- "\\bar {\\mathbf x} &= \\mathbf x \\ast f_{\\mathbf x}(\\bullet)\\, \\, &\\text{Prediction} \\\\\n",
- "\\mathbf x &= \\mathcal L \\cdot \\bar{\\mathbf x}\\, \\, &\\text{Correction}\n",
- "\\end{aligned}$$\n",
- "\n",
- "\n",
- "$\\bar{\\mathbf x}$ is the *prior* \n",
- "\n",
- "$\\mathcal L$ is the *likelihood* of a measurement given the prior $\\bar{\\mathbf x}$\n",
- "\n",
- "$f_{\\mathbf x}(\\bullet)$ is the *process model* or the gaussian term that helps predict the next state like velocity\n",
- "to track position or acceleration.\n",
- "\n",
- "$\\ast$ denotes *convolution*.\n",
- "\n",
- "\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Kalman Gain\n",
- "\n",
- "\n",
- "$$ x = (\\mathcal L \\bar x)$$\n",
- "\n",
- "Where x is posterior and $\\mathcal L$ and $\\bar x$ are gaussians.\n",
- "\n",
- "Therefore the mean of the posterior is given by:\n",
- "\n",
- "$$\n",
- "\\mu=\\frac{\\bar\\sigma^2\\, \\mu_z + \\sigma_z^2 \\, \\bar\\mu} {\\bar\\sigma^2 + \\sigma_z^2}\n",
- "$$\n",
- "\n",
- "\n",
- "$$\\mu = \\left( \\frac{\\bar\\sigma^2}{\\bar\\sigma^2 + \\sigma_z^2}\\right) \\mu_z + \\left(\\frac{\\sigma_z^2}{\\bar\\sigma^2 + \\sigma_z^2}\\right)\\bar\\mu$$\n",
- "\n",
- "In this form it is easy to see that we are scaling the measurement and the prior by weights: \n",
- "\n",
- "$$\\mu = W_1 \\mu_z + W_2 \\bar\\mu$$\n",
- "\n",
- "\n",
- "The weights sum to one because the denominator is a normalization term. We introduce a new term, $K=W_1$, giving us:\n",
- "\n",
- "$$\\begin{aligned}\n",
- "\\mu &= K \\mu_z + (1-K) \\bar\\mu\\\\\n",
- "&= \\bar\\mu + K(\\mu_z - \\bar\\mu)\n",
- "\\end{aligned}$$\n",
- "\n",
- "where\n",
- "\n",
- "$$K = \\frac {\\bar\\sigma^2}{\\bar\\sigma^2 + \\sigma_z^2}$$\n",
- "\n",
- "The variance in terms of the Kalman gain:\n",
- "\n",
- "$$\\begin{aligned}\n",
- "\\sigma^2 &= \\frac{\\bar\\sigma^2 \\sigma_z^2 } {\\bar\\sigma^2 + \\sigma_z^2} \\\\\n",
- "&= K\\sigma_z^2 \\\\\n",
- "&= (1-K)\\bar\\sigma^2 \n",
- "\\end{aligned}$$\n",
- "\n",
- "\n",
- "$K$ is the *Kalman gain*. It's the crux of the Kalman filter. It is a scaling term that chooses a value partway between $\\mu_z$ and $\\bar\\mu$."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Kalman Filter - Univariate and Multivariate\n",
- "\n",
- "\n",
- "**Prediction** \n",
- "\n",
- "$\\begin{array}{|l|l|l|}\n",
- "\\hline\n",
- "\\text{Univariate} & \\text{Univariate} & \\text{Multivariate}\\\\\n",
- "& \\text{(Kalman form)} & \\\\\n",
- "\\hline\n",
- "\\bar \\mu = \\mu + \\mu_{f_x} & \\bar x = x + dx & \\bar{\\mathbf x} = \\mathbf{Fx} + \\mathbf{Bu}\\\\\n",
- "\\bar\\sigma^2 = \\sigma_x^2 + \\sigma_{f_x}^2 & \\bar P = P + Q & \\bar{\\mathbf P} = \\mathbf{FPF}^\\mathsf T + \\mathbf Q \\\\\n",
- "\\hline\n",
- "\\end{array}$\n",
- "\n",
- "$\\mathbf x,\\, \\mathbf P$ are the state mean and covariance. They correspond to $x$ and $\\sigma^2$.\n",
- "\n",
- "$\\mathbf F$ is the *state transition function*. When multiplied by $\\bf x$ it computes the prior. \n",
- "\n",
- "$\\mathbf Q$ is the process covariance. It corresponds to $\\sigma^2_{f_x}$.\n",
- "\n",
- "$\\mathbf B$ and $\\mathbf u$ are model control inputs to the system.\n",
- "\n",
- "**Correction** \n",
- "\n",
- "$\\begin{array}{|l|l|l|}\n",
- "\\hline\n",
- "\\text{Univariate} & \\text{Univariate} & \\text{Multivariate}\\\\\n",
- "& \\text{(Kalman form)} & \\\\\n",
- "\\hline\n",
- "& y = z - \\bar x & \\mathbf y = \\mathbf z - \\mathbf{H\\bar x} \\\\\n",
- "& K = \\frac{\\bar P}{\\bar P+R}&\n",
- "\\mathbf K = \\mathbf{\\bar{P}H}^\\mathsf T (\\mathbf{H\\bar{P}H}^\\mathsf T + \\mathbf R)^{-1} \\\\\n",
- "\\mu=\\frac{\\bar\\sigma^2\\, \\mu_z + \\sigma_z^2 \\, \\bar\\mu} {\\bar\\sigma^2 + \\sigma_z^2} & x = \\bar x + Ky & \\mathbf x = \\bar{\\mathbf x} + \\mathbf{Ky} \\\\\n",
- "\\sigma^2 = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2} & P = (1-K)\\bar P &\n",
- "\\mathbf P = (\\mathbf I - \\mathbf{KH})\\mathbf{\\bar{P}} \\\\\n",
- "\\hline\n",
- "\\end{array}$\n",
- "\n",
- "$\\mathbf H$ is the measurement function.\n",
- "\n",
- "$\\mathbf z,\\, \\mathbf R$ are the measurement mean and noise covariance. They correspond to $z$ and $\\sigma_z^2$ in the univariate filter. \n",
- "$\\mathbf y$ and $\\mathbf K$ are the residual and Kalman gain. \n",
- "\n",
- "The details will be different than the univariate filter because these are vectors and matrices, but the concepts are exactly the same: \n",
- "\n",
- "- Use a Gaussian to represent our estimate of the state and error\n",
- "- Use a Gaussian to represent the measurement and its error\n",
- "- Use a Gaussian to represent the process model\n",
- "- Use the process model to predict the next state (the prior)\n",
- "- Form an estimate part way between the measurement and the prior"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### References:\n",
- "\n",
- "1. Roger Labbe's [repo](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python) on Kalman Filters. (Majority of text in the notes are from this)\n",
- "\n",
- "\n",
- "\n",
- "2. Probabilistic Robotics by Sebastian Thrun, Wolfram Burgard and Dieter Fox, MIT Press.\n"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.6"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/Localization/__init__.py b/Localization/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/Localization/bayes_filter.png b/Localization/bayes_filter.png
deleted file mode 100644
index 50e509bdac..0000000000
Binary files a/Localization/bayes_filter.png and /dev/null differ
diff --git a/Localization/cubature_kalman_filter/cubature_kalman_filter.py b/Localization/cubature_kalman_filter/cubature_kalman_filter.py
new file mode 100644
index 0000000000..0fc4c93760
--- /dev/null
+++ b/Localization/cubature_kalman_filter/cubature_kalman_filter.py
@@ -0,0 +1,246 @@
+"""
+Cubature Kalman filter using Constant Turn Rate and Velocity (CTRV) model
+Fuse sensor data from IMU and GPS to obtain accurate position
+
+https://ieeexplore.ieee.org/document/4982682
+
+Author: Raghuram Shankar
+
+state matrix: 2D x-y position, yaw, velocity and yaw rate
+measurement matrix: 2D x-y position, velocity and yaw rate
+
+dt: Duration of time step
+N: Number of time steps
+show_final: Flag for showing final result
+show_animation: Flag for showing each animation frame
+show_ellipse: Flag for showing covariance ellipse
+z_noise: Measurement noise
+x_0: Prior state estimate matrix
+P_0: Prior state estimate covariance matrix
+q: Process noise covariance
+hx: Measurement model matrix
+r: Sensor noise covariance
+SP: Sigma Points
+W: Weights
+
+x_est: State estimate
+P_est: State estimate covariance
+x_true: Ground truth value of state
+x_true_cat: Concatenate all ground truth states
+x_est_cat: Concatenate all state estimates
+z_cat: Concatenate all measurements
+
+"""
+
+import math
+import matplotlib.pyplot as plt
+import numpy as np
+from scipy.linalg import sqrtm
+
+
+dt = 0.1
+N = 100
+
+show_final = 1
+show_animation = 0
+show_ellipse = 0
+
+
+z_noise = np.array([[0.1, 0.0, 0.0, 0.0], # x position [m]
+ [0.0, 0.1, 0.0, 0.0], # y position [m]
+ [0.0, 0.0, 0.1, 0.0], # velocity [m/s]
+ [0.0, 0.0, 0.0, 0.1]]) # yaw rate [rad/s]
+
+
+x_0 = np.array([[0.0], # x position [m]
+ [0.0], # y position [m]
+ [0.0], # yaw [rad]
+ [1.0], # velocity [m/s]
+ [0.1]]) # yaw rate [rad/s]
+
+
+p_0 = np.array([[1e-3, 0.0, 0.0, 0.0, 0.0],
+ [0.0, 1e-3, 0.0, 0.0, 0.0],
+ [0.0, 0.0, 1.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, 1.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, 1.0]])
+
+
+q = np.array([[1e-11, 0.0, 0.0, 0.0, 0.0],
+ [0.0, 1e-11, 0.0, 0.0, 0.0],
+ [0.0, 0.0, np.deg2rad(1e-4), 0.0, 0.0],
+ [0.0, 0.0, 0.0, 1e-4, 0.0],
+ [0.0, 0.0, 0.0, 0.0, np.deg2rad(1e-4)]])
+
+
+hx = np.array([[1.0, 0.0, 0.0, 0.0, 0.0],
+ [0.0, 1.0, 0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, 1.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, 1.0]])
+
+
+r = np.array([[0.015, 0.0, 0.0, 0.0],
+ [0.0, 0.010, 0.0, 0.0],
+ [0.0, 0.0, 0.1, 0.0],
+ [0.0, 0.0, 0.0, 0.01]])**2
+
+
+def cubature_kalman_filter(x_est, p_est, z):
+ x_pred, p_pred = cubature_prediction(x_est, p_est)
+ x_upd, p_upd = cubature_update(x_pred, p_pred, z)
+ return x_upd, p_upd
+
+
+def f(x):
+ """
+ Motion Model
+ References:
+ http://fusion.isif.org/proceedings/fusion08CD/papers/1569107835.pdf
+ https://github.com/balzer82/Kalman
+ """
+ x[0] = x[0] + (x[3]/x[4]) * (np.sin(x[4] * dt + x[2]) - np.sin(x[2]))
+ x[1] = x[1] + (x[3]/x[4]) * (- np.cos(x[4] * dt + x[2]) + np.cos(x[2]))
+ x[2] = x[2] + x[4] * dt
+ x[3] = x[3]
+ x[4] = x[4]
+ return x
+
+
+def h(x):
+ """Measurement Model"""
+ x = hx @ x
+ return x
+
+
+def sigma(x, p):
+ """
+ Unscented Transform with Cubature Rule
+ Generate 2n Sigma Points to represent the nonlinear motion
+ Assign Weights to each Sigma Point, Wi = 1/2n
+ Cubature Rule - Special Case of Unscented Transform
+ W0 = 0, no extra tuning parameters, no negative weights
+ """
+ n = np.shape(x)[0]
+ SP = np.zeros((n, 2*n))
+ W = np.zeros((1, 2*n))
+ for i in range(n):
+ SD = sqrtm(p)
+ SP[:, i] = (x + (math.sqrt(n) * SD[:, i]).reshape((n, 1))).flatten()
+ SP[:, i+n] = (x - (math.sqrt(n) * SD[:, i]).reshape((n, 1))).flatten()
+ W[:, i] = 1/(2*n)
+ W[:, i+n] = W[:, i]
+ return SP, W
+
+
+def cubature_prediction(x_pred, p_pred):
+ n = np.shape(x_pred)[0]
+ [SP, W] = sigma(x_pred, p_pred)
+ x_pred = np.zeros((n, 1))
+ p_pred = q
+ for i in range(2*n):
+ x_pred = x_pred + (f(SP[:, i]).reshape((n, 1)) * W[0, i])
+ for i in range(2*n):
+ p_step = (f(SP[:, i]).reshape((n, 1)) - x_pred)
+ p_pred = p_pred + (p_step @ p_step.T * W[0, i])
+ return x_pred, p_pred
+
+
+def cubature_update(x_pred, p_pred, z):
+ n = np.shape(x_pred)[0]
+ m = np.shape(z)[0]
+ [SP, W] = sigma(x_pred, p_pred)
+ y_k = np.zeros((m, 1))
+ P_xy = np.zeros((n, m))
+ s = r
+ for i in range(2*n):
+ y_k = y_k + (h(SP[:, i]).reshape((m, 1)) * W[0, i])
+ for i in range(2*n):
+ p_step = (h(SP[:, i]).reshape((m, 1)) - y_k)
+ P_xy = P_xy + ((SP[:, i]).reshape((n, 1)) -
+ x_pred) @ p_step.T * W[0, i]
+ s = s + p_step @ p_step.T * W[0, i]
+ x_pred = x_pred + P_xy @ np.linalg.pinv(s) @ (z - y_k)
+ p_pred = p_pred - P_xy @ np.linalg.pinv(s) @ P_xy.T
+ return x_pred, p_pred
+
+
+def generate_measurement(x_true):
+ gz = hx @ x_true
+ z = gz + z_noise @ np.random.randn(4, 1)
+ return z
+
+
+def plot_animation(i, x_true_cat, x_est_cat, z):
+ if i == 0:
+ plt.plot(x_true_cat[0], x_true_cat[1], '.r')
+ plt.plot(x_est_cat[0], x_est_cat[1], '.b')
+ else:
+ plt.plot(x_true_cat[0:, 0], x_true_cat[0:, 1], 'r')
+ plt.plot(x_est_cat[0:, 0], x_est_cat[0:, 1], 'b')
+ plt.plot(z[0], z[1], '+g')
+ plt.grid(True)
+ plt.pause(0.001)
+
+
+def plot_ellipse(x_est, p_est):
+ phi = np.linspace(0, 2 * math.pi, 100)
+ p_ellipse = np.array(
+ [[p_est[0, 0], p_est[0, 1]], [p_est[1, 0], p_est[1, 1]]])
+ x0 = 3 * sqrtm(p_ellipse)
+ xy_1 = np.array([])
+ xy_2 = np.array([])
+ for i in range(100):
+ arr = np.array([[math.sin(phi[i])], [math.cos(phi[i])]])
+ arr = x0 @ arr
+ xy_1 = np.hstack([xy_1, arr[0]])
+ xy_2 = np.hstack([xy_2, arr[1]])
+ plt.plot(xy_1 + x_est[0], xy_2 + x_est[1], 'r')
+ plt.pause(0.00001)
+
+
+def plot_final(x_true_cat, x_est_cat, z_cat):
+ fig = plt.figure()
+ subplot = fig.add_subplot(111)
+ subplot.plot(x_true_cat[0:, 0], x_true_cat[0:, 1],
+ 'r', label='True Position')
+ subplot.plot(x_est_cat[0:, 0], x_est_cat[0:, 1],
+ 'b', label='Estimated Position')
+ subplot.plot(z_cat[0:, 0], z_cat[0:, 1], '+g', label='Noisy Measurements')
+ subplot.set_xlabel('x [m]')
+ subplot.set_ylabel('y [m]')
+ subplot.set_title('Cubature Kalman Filter - CTRV Model')
+ subplot.legend(loc='upper left', shadow=True, fontsize='large')
+ plt.grid(True)
+ plt.show()
+
+
+def main():
+ print(__file__ + " start!!")
+ x_est = x_0
+ p_est = p_0
+ x_true = x_0
+ x_true_cat = np.array([x_0[0, 0], x_0[1, 0]])
+ x_est_cat = np.array([x_0[0, 0], x_0[1, 0]])
+ z_cat = np.array([x_0[0, 0], x_0[1, 0]])
+ for i in range(N):
+ x_true = f(x_true)
+ z = generate_measurement(x_true)
+ if i == (N - 1) and show_final == 1:
+ show_final_flag = 1
+ else:
+ show_final_flag = 0
+ if show_animation == 1:
+ plot_animation(i, x_true_cat, x_est_cat, z)
+ if show_ellipse == 1:
+ plot_ellipse(x_est[0:2], p_est)
+ if show_final_flag == 1:
+ plot_final(x_true_cat, x_est_cat, z_cat)
+ x_est, p_est = cubature_kalman_filter(x_est, p_est, z)
+ x_true_cat = np.vstack((x_true_cat, x_true[0:2].T))
+ x_est_cat = np.vstack((x_est_cat, x_est[0:2].T))
+ z_cat = np.vstack((z_cat, z[0:2].T))
+ print('CKF Over')
+
+
+if __name__ == '__main__':
+ main()
diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py
index 5ca7713b7d..e8a988a270 100644
--- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py
+++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py
@@ -1,22 +1,28 @@
-
"""
Ensemble Kalman Filter(EnKF) localization sample
author: Ryohei Sasaki(rsasaki0109)
-Ref:
-- [Ensemble Kalman filtering](https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135)
+Reference:
+Ensemble Kalman filtering
+(https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135)
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
-import numpy as np
import math
import matplotlib.pyplot as plt
+import numpy as np
+from utils.angle import angle_mod
+
+from utils.angle import rot_mat_2d
# Simulation parameter
-Qsim = np.diag([0.2, np.deg2rad(1.0)])**2
-Rsim = np.diag([1.0, np.deg2rad(30.0)])**2
+Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2
+R_sim = np.diag([1.0, np.deg2rad(30.0)]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
@@ -30,13 +36,12 @@
def calc_input():
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
- u = np.array([[v, yawrate]]).T
+ yaw_rate = 0.1 # [rad/s]
+ u = np.array([[v, yaw_rate]]).T
return u
def observation(xTrue, xd, u, RFID):
-
xTrue = motion_model(xTrue, u)
z = np.zeros((0, 4))
@@ -45,18 +50,18 @@ def observation(xTrue, xd, u, RFID):
dx = RFID[i, 0] - xTrue[0, 0]
dy = RFID[i, 1] - xTrue[1, 0]
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
- zi = np.array([dn, anglen, RFID[i, 0], RFID[i, 1]])
+ dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise
+ angle_with_noise = angle + np.random.randn() * Q_sim[1, 1] ** 0.5
+ zi = np.array([dn, angle_with_noise, RFID[i, 0], RFID[i, 1]])
z = np.vstack((z, zi))
# add noise to input
ud = np.array([[
- u[0, 0] + np.random.randn() * Rsim[0, 0],
- u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T
+ u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5,
+ u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T
xd = motion_model(xd, ud)
return xTrue, z, xd, ud
@@ -77,15 +82,15 @@ def motion_model(x, u):
return x
-def calc_LM_Pos(x, landmarks):
- landmarks_pos = np.zeros((2*landmarks.shape[0], 1))
+def observe_landmark_position(x, landmarks):
+ landmarks_pos = np.zeros((2 * landmarks.shape[0], 1))
for (i, lm) in enumerate(landmarks):
- landmarks_pos[2*i] = x[0, 0] + lm[0] * \
- math.cos(x[2, 0] + lm[1]) + np.random.randn() * \
- Qsim[0, 0]/np.sqrt(2)
- landmarks_pos[2*i+1] = x[1, 0] + lm[0] * \
- math.sin(x[2, 0] + lm[1]) + np.random.randn() * \
- Qsim[0, 0]/np.sqrt(2)
+ index = 2 * i
+ q = Q_sim[0, 0] ** 0.5
+ landmarks_pos[index] = x[0, 0] + lm[0] * math.cos(
+ x[2, 0] + lm[1]) + np.random.randn() * q / np.sqrt(2)
+ landmarks_pos[index + 1] = x[1, 0] + lm[0] * math.sin(
+ x[2, 0] + lm[1]) + np.random.randn() * q / np.sqrt(2)
return landmarks_pos
@@ -95,25 +100,26 @@ def calc_covariance(xEst, px):
for i in range(px.shape[1]):
dx = (px[:, i] - xEst)[0:3]
cov += dx.dot(dx.T)
+ cov /= NP
return cov
-def enkf_localization(px, xEst, PEst, z, u):
+def enkf_localization(px, z, u):
"""
Localization with Ensemble Kalman filter
"""
- pz = np.zeros((z.shape[0]*2, NP)) # Particle store of z
+ pz = np.zeros((z.shape[0] * 2, NP)) # Particle store of z
for ip in range(NP):
x = np.array([px[:, ip]]).T
# Predict with random input sampling
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
+ ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5
+ ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5
ud = np.array([[ud1, ud2]]).T
x = motion_model(x, ud)
px[:, ip] = x[:, 0]
- z_pos = calc_LM_Pos(x, z)
+ z_pos = observe_landmark_position(x, z)
pz[:, ip] = z_pos[:, 0]
x_ave = np.mean(px, axis=1)
@@ -122,12 +128,12 @@ def enkf_localization(px, xEst, PEst, z, u):
z_ave = np.mean(pz, axis=1)
z_dif = pz - np.tile(z_ave, (NP, 1)).T
- U = 1/(NP-1) * x_dif @ z_dif.T
- V = 1/(NP-1) * z_dif @ z_dif.T
+ U = 1 / (NP - 1) * x_dif @ z_dif.T
+ V = 1 / (NP - 1) * z_dif @ z_dif.T
K = U @ np.linalg.inv(V) # Kalman Gain
- z_lm_pos = z[:, [2, 3]].reshape(-1,)
+ z_lm_pos = z[:, [2, 3]].reshape(-1, )
px_hat = px + K @ (np.tile(z_lm_pos, (NP, 1)).T - pz)
@@ -139,42 +145,42 @@ def enkf_localization(px, xEst, PEst, z, u):
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
Pxy = PEst[0:2, 0:2]
- eigval, eigvec = np.linalg.eig(Pxy)
+ eig_val, eig_vec = np.linalg.eig(Pxy)
- if eigval[0] >= eigval[1]:
- bigind = 0
- smallind = 1
+ if eig_val[0] >= eig_val[1]:
+ big_ind = 0
+ small_ind = 1
else:
- bigind = 1
- smallind = 0
+ big_ind = 1
+ small_ind = 0
t = np.arange(0, 2 * math.pi + 0.1, 0.1)
- # eigval[bigind] or eiqval[smallind] were occassionally negative numbers extremely
- # close to 0 (~10^-20), catch these cases and set the respective variable to 0
+ # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative
+ # numbers extremely close to 0 (~10^-20), catch these cases and set
+ # the respective variable to 0
try:
- a = math.sqrt(eigval[bigind])
+ a = math.sqrt(eig_val[big_ind])
except ValueError:
a = 0
try:
- b = math.sqrt(eigval[smallind])
+ b = math.sqrt(eig_val[small_ind])
except ValueError:
b = 0
x = [a * math.cos(it) for it in t]
y = [b * math.sin(it) for it in t]
- angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
- R = np.array([[math.cos(angle), math.sin(angle)],
- [-math.sin(angle), math.cos(angle)]])
- fx = R.dot(np.array([[x, y]]))
- px = np.array(fx[0, :] + xEst[0, 0]).flatten()
- py = np.array(fx[1, :] + xEst[1, 0]).flatten()
+ angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind])
+ fx = np.stack([x, y]).T @ rot_mat_2d(angle)
+
+ px = np.array(fx[:, 0] + xEst[0, 0]).flatten()
+ py = np.array(fx[:, 1] + xEst[1, 0]).flatten()
plt.plot(px, py, "--r")
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def main():
@@ -182,17 +188,15 @@ def main():
time = 0.0
- # RFID positions [x, y]
- RFID = np.array([[10.0, 0.0],
- [10.0, 10.0],
- [0.0, 15.0],
- [-5.0, 20.0]])
+ # RF_ID positions [x, y]
+ RF_ID = np.array([[10.0, 0.0],
+ [10.0, 10.0],
+ [0.0, 15.0],
+ [-5.0, 20.0]])
# State Vector [x y yaw v]'
xEst = np.zeros((4, 1))
xTrue = np.zeros((4, 1))
- PEst = np.eye(4)
-
px = np.zeros((4, NP)) # Particle store of x
xDR = np.zeros((4, 1)) # Dead reckoning
@@ -206,9 +210,9 @@ def main():
time += DT
u = calc_input()
- xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+ xTrue, z, xDR, ud = observation(xTrue, xDR, u, RF_ID)
- xEst, PEst, px = enkf_localization(px, xEst, PEst, z, ud)
+ xEst, PEst, px = enkf_localization(px, z, ud)
# store data history
hxEst = np.hstack((hxEst, xEst))
@@ -217,10 +221,14 @@ def main():
if show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
for i in range(len(z[:, 0])):
plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k")
- plt.plot(RFID[:, 0], RFID[:, 1], "*k")
+ plt.plot(RF_ID[:, 0], RF_ID[:, 1], "*k")
plt.plot(px[0, :], px[1, :], ".r")
plt.plot(np.array(hxTrue[0, :]).flatten(),
np.array(hxTrue[1, :]).flatten(), "-b")
@@ -228,7 +236,7 @@ def main():
np.array(hxDR[1, :]).flatten(), "-k")
plt.plot(np.array(hxEst[0, :]).flatten(),
np.array(hxEst[1, :]).flatten(), "-r")
- #plot_covariance_ellipse(xEst, PEst)
+ plot_covariance_ellipse(xEst, PEst)
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
@@ -236,4 +244,3 @@ def main():
if __name__ == '__main__':
main()
-
diff --git a/Localization/extended_kalman_filter/ekf.png b/Localization/extended_kalman_filter/ekf.png
deleted file mode 100644
index fb4e660011..0000000000
Binary files a/Localization/extended_kalman_filter/ekf.png and /dev/null differ
diff --git a/Localization/extended_kalman_filter/ekf_with_velocity_correction.py b/Localization/extended_kalman_filter/ekf_with_velocity_correction.py
new file mode 100644
index 0000000000..5dd97830fc
--- /dev/null
+++ b/Localization/extended_kalman_filter/ekf_with_velocity_correction.py
@@ -0,0 +1,198 @@
+"""
+
+Extended kalman filter (EKF) localization with velocity correction sample
+
+author: Atsushi Sakai (@Atsushi_twi)
+modified by: Ryohei Sasaki (@rsasaki0109)
+
+"""
+import sys
+import pathlib
+
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
+import math
+import matplotlib.pyplot as plt
+import numpy as np
+
+from utils.plot import plot_covariance_ellipse
+
+# Covariance for EKF simulation
+Q = np.diag([
+ 0.1, # variance of location on x-axis
+ 0.1, # variance of location on y-axis
+ np.deg2rad(1.0), # variance of yaw angle
+ 0.4, # variance of velocity
+ 0.1 # variance of scale factor
+]) ** 2 # predict state covariance
+R = np.diag([0.1, 0.1]) ** 2 # Observation x,y position covariance
+
+# Simulation parameter
+INPUT_NOISE = np.diag([0.1, np.deg2rad(5.0)]) ** 2
+GPS_NOISE = np.diag([0.05, 0.05]) ** 2
+
+DT = 0.1 # time tick [s]
+SIM_TIME = 50.0 # simulation time [s]
+
+show_animation = True
+
+
+def calc_input():
+ v = 1.0 # [m/s]
+ yawrate = 0.1 # [rad/s]
+ u = np.array([[v], [yawrate]])
+ return u
+
+
+def observation(xTrue, xd, u):
+ xTrue = motion_model(xTrue, u)
+
+ # add noise to gps x-y
+ z = observation_model(xTrue) + GPS_NOISE @ np.random.randn(2, 1)
+
+ # add noise to input
+ ud = u + INPUT_NOISE @ np.random.randn(2, 1)
+
+ xd = motion_model(xd, ud)
+
+ return xTrue, z, xd, ud
+
+
+def motion_model(x, u):
+ F = np.array([[1.0, 0, 0, 0, 0],
+ [0, 1.0, 0, 0, 0],
+ [0, 0, 1.0, 0, 0],
+ [0, 0, 0, 0, 0],
+ [0, 0, 0, 0, 1.0]])
+
+ B = np.array([[DT * math.cos(x[2, 0]) * x[4, 0], 0],
+ [DT * math.sin(x[2, 0]) * x[4, 0], 0],
+ [0.0, DT],
+ [1.0, 0.0],
+ [0.0, 0.0]])
+
+ x = F @ x + B @ u
+
+ return x
+
+
+def observation_model(x):
+ H = np.array([
+ [1, 0, 0, 0, 0],
+ [0, 1, 0, 0, 0]
+ ])
+ z = H @ x
+
+ return z
+
+
+def jacob_f(x, u):
+ """
+ Jacobian of Motion Model
+
+ motion model
+ x_{t+1} = x_t+v*s*dt*cos(yaw)
+ y_{t+1} = y_t+v*s*dt*sin(yaw)
+ yaw_{t+1} = yaw_t+omega*dt
+ v_{t+1} = v{t}
+ s_{t+1} = s{t}
+ so
+ dx/dyaw = -v*s*dt*sin(yaw)
+ dx/dv = dt*s*cos(yaw)
+ dx/ds = dt*v*cos(yaw)
+ dy/dyaw = v*s*dt*cos(yaw)
+ dy/dv = dt*s*sin(yaw)
+ dy/ds = dt*v*sin(yaw)
+ """
+ yaw = x[2, 0]
+ v = u[0, 0]
+ s = x[4, 0]
+ jF = np.array([
+ [1.0, 0.0, -DT * v * s * math.sin(yaw), DT * s * math.cos(yaw), DT * v * math.cos(yaw)],
+ [0.0, 1.0, DT * v * s * math.cos(yaw), DT * s * math.sin(yaw), DT * v * math.sin(yaw)],
+ [0.0, 0.0, 1.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, 1.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, 1.0]])
+ return jF
+
+
+def jacob_h():
+ jH = np.array([[1, 0, 0, 0, 0],
+ [0, 1, 0, 0, 0]])
+ return jH
+
+
+def ekf_estimation(xEst, PEst, z, u):
+ # Predict
+ xPred = motion_model(xEst, u)
+ jF = jacob_f(xEst, u)
+ PPred = jF @ PEst @ jF.T + Q
+
+ # Update
+ jH = jacob_h()
+ zPred = observation_model(xPred)
+ y = z - zPred
+ S = jH @ PPred @ jH.T + R
+ K = PPred @ jH.T @ np.linalg.inv(S)
+ xEst = xPred + K @ y
+ PEst = (np.eye(len(xEst)) - K @ jH) @ PPred
+ return xEst, PEst
+
+
+def main():
+ print(__file__ + " start!!")
+
+ time = 0.0
+
+ # State Vector [x y yaw v s]'
+ xEst = np.zeros((5, 1))
+ xEst[4, 0] = 1.0 # Initial scale factor
+ xTrue = np.zeros((5, 1))
+ true_scale_factor = 0.9 # True scale factor
+ xTrue[4, 0] = true_scale_factor
+ PEst = np.eye(5)
+
+ xDR = np.zeros((5, 1)) # Dead reckoning
+
+ # history
+ hxEst = xEst
+ hxTrue = xTrue
+ hxDR = xTrue
+ hz = np.zeros((2, 1))
+
+ while SIM_TIME >= time:
+ time += DT
+ u = calc_input()
+
+ xTrue, z, xDR, ud = observation(xTrue, xDR, u)
+
+ xEst, PEst = ekf_estimation(xEst, PEst, z, ud)
+
+ # store data history
+ hxEst = np.hstack((hxEst, xEst))
+ hxDR = np.hstack((hxDR, xDR))
+ hxTrue = np.hstack((hxTrue, xTrue))
+ hz = np.hstack((hz, z))
+ estimated_scale_factor = hxEst[4, -1]
+ if show_animation:
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(hz[0, :], hz[1, :], ".g")
+ plt.plot(hxTrue[0, :].flatten(),
+ hxTrue[1, :].flatten(), "-b")
+ plt.plot(hxDR[0, :].flatten(),
+ hxDR[1, :].flatten(), "-k")
+ plt.plot(hxEst[0, :].flatten(),
+ hxEst[1, :].flatten(), "-r")
+ plt.text(0.45, 0.85, f"True Velocity Scale Factor: {true_scale_factor:.2f}", ha='left', va='top', transform=plt.gca().transAxes)
+ plt.text(0.45, 0.95, f"Estimated Velocity Scale Factor: {estimated_scale_factor:.2f}", ha='left', va='top', transform=plt.gca().transAxes)
+ plot_covariance_ellipse(xEst[0, 0], xEst[1, 0], PEst)
+ plt.axis("equal")
+ plt.grid(True)
+ plt.pause(0.001)
+
+
+if __name__ == '__main__':
+ main()
diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py
index 3f0589b8c6..d9ece6c6f3 100644
--- a/Localization/extended_kalman_filter/extended_kalman_filter.py
+++ b/Localization/extended_kalman_filter/extended_kalman_filter.py
@@ -5,23 +5,29 @@
author: Atsushi Sakai (@Atsushi_twi)
"""
+import sys
+import pathlib
+
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import math
-import numpy as np
import matplotlib.pyplot as plt
+import numpy as np
+
+from utils.plot import plot_covariance_ellipse
# Covariance for EKF simulation
Q = np.diag([
- 0.1, # variance of location on x-axis
- 0.1, # variance of location on y-axis
- np.deg2rad(1.0), # variance of yaw angle
- 1.0 # variance of velocity
- ])**2 # predict state covariance
-R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance
+ 0.1, # variance of location on x-axis
+ 0.1, # variance of location on y-axis
+ np.deg2rad(1.0), # variance of yaw angle
+ 1.0 # variance of velocity
+]) ** 2 # predict state covariance
+R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance
# Simulation parameter
-INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2
-GPS_NOISE = np.diag([0.5, 0.5])**2
+INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2
+GPS_NOISE = np.diag([0.5, 0.5]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
@@ -37,7 +43,6 @@ def calc_input():
def observation(xTrue, xd, u):
-
xTrue = motion_model(xTrue, u)
# add noise to gps x-y
@@ -52,7 +57,6 @@ def observation(xTrue, xd, u):
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0, 0],
[0, 1.0, 0, 0],
[0, 0, 1.0, 0],
@@ -79,7 +83,7 @@ def observation_model(x):
return z
-def jacobF(x, u):
+def jacob_f(x, u):
"""
Jacobian of Motion Model
@@ -105,7 +109,7 @@ def jacobF(x, u):
return jF
-def jacobH(x):
+def jacob_h():
# Jacobian of Observation Model
jH = np.array([
[1, 0, 0, 0],
@@ -116,49 +120,22 @@ def jacobH(x):
def ekf_estimation(xEst, PEst, z, u):
-
# Predict
xPred = motion_model(xEst, u)
- jF = jacobF(xPred, u)
- PPred = jF@PEst@jF.T + Q
+ jF = jacob_f(xEst, u)
+ PPred = jF @ PEst @ jF.T + Q
# Update
- jH = jacobH(xPred)
+ jH = jacob_h()
zPred = observation_model(xPred)
y = z - zPred
- S = jH@PPred@jH.T + R
- K = PPred@jH.T@np.linalg.inv(S)
- xEst = xPred + K@y
- PEst = (np.eye(len(xEst)) - K@jH)@PPred
-
+ S = jH @ PPred @ jH.T + R
+ K = PPred @ jH.T @ np.linalg.inv(S)
+ xEst = xPred + K @ y
+ PEst = (np.eye(len(xEst)) - K @ jH) @ PPred
return xEst, PEst
-def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
- Pxy = PEst[0:2, 0:2]
- eigval, eigvec = np.linalg.eig(Pxy)
-
- if eigval[0] >= eigval[1]:
- bigind = 0
- smallind = 1
- else:
- bigind = 1
- smallind = 0
-
- t = np.arange(0, 2 * math.pi + 0.1, 0.1)
- a = math.sqrt(eigval[bigind])
- b = math.sqrt(eigval[smallind])
- x = [a * math.cos(it) for it in t]
- y = [b * math.sin(it) for it in t]
- angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
- R = np.array([[math.cos(angle), math.sin(angle)],
- [-math.sin(angle), math.cos(angle)]])
- fx = R@(np.array([x, y]))
- px = np.array(fx[0, :] + xEst[0, 0]).flatten()
- py = np.array(fx[1, :] + xEst[1, 0]).flatten()
- plt.plot(px, py, "--r")
-
-
def main():
print(__file__ + " start!!")
@@ -193,6 +170,9 @@ def main():
if show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(hz[0, :], hz[1, :], ".g")
plt.plot(hxTrue[0, :].flatten(),
hxTrue[1, :].flatten(), "-b")
@@ -200,7 +180,7 @@ def main():
hxDR[1, :].flatten(), "-k")
plt.plot(hxEst[0, :].flatten(),
hxEst[1, :].flatten(), "-r")
- plot_covariance_ellipse(xEst, PEst)
+ plot_covariance_ellipse(xEst[0, 0], xEst[1, 0], PEst)
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
diff --git a/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb b/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb
deleted file mode 100644
index 073fd06a16..0000000000
--- a/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb
+++ /dev/null
@@ -1,264 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Extended Kalman Filter Localization"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 2,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"ekf.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\n",
- "\n",
- "This is a sensor fusion localization with Extended Kalman Filter(EKF).\n",
- "\n",
- "The blue line is true trajectory, the black line is dead reckoning\n",
- "trajectory,\n",
- "\n",
- "the green point is positioning observation (ex. GPS), and the red line\n",
- "is estimated trajectory with EKF.\n",
- "\n",
- "The red ellipse is estimated covariance ellipse with EKF.\n",
- "\n",
- "Code: [PythonRobotics/extended\\_kalman\\_filter\\.py at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics/blob/master/Localization/extended_kalman_filter/extended_kalman_filter.py)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Filter design\n",
- "\n",
- "In this simulation, the robot has a state vector includes 4 states at time $t$.\n",
- "\n",
- "$$\\textbf{x}_t=[x_t, y_t, \\phi_t, v_t]$$\n",
- "\n",
- "x, y are a 2D x-y position, $\\phi$ is orientation, and v is velocity.\n",
- "\n",
- "In the code, \"xEst\" means the state vector. [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L168)\n",
- "\n",
- "And, $P_t$ is covariace matrix of the state,\n",
- "\n",
- "$Q$ is covariance matrix of process noise, \n",
- "\n",
- "$R$ is covariance matrix of observation noise at time $t$ \n",
- "\n",
- " \n",
- "\n",
- "The robot has a speed sensor and a gyro sensor.\n",
- "\n",
- "So, the input vecor can be used as each time step\n",
- "\n",
- "$$\\textbf{u}_t=[v_t, \\omega_t]$$\n",
- "\n",
- "Also, the robot has a GNSS sensor, it means that the robot can observe x-y position at each time.\n",
- "\n",
- "$$\\textbf{z}_t=[x_t,y_t]$$\n",
- "\n",
- "The input and observation vector includes sensor noise.\n",
- "\n",
- "In the code, \"observation\" function generates the input and observation vector with noise [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L34-L50)\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Motion Model\n",
- "\n",
- "The robot model is \n",
- "\n",
- "$$ \\dot{x} = vcos(\\phi)$$\n",
- "\n",
- "$$ \\dot{y} = vsin((\\phi)$$\n",
- "\n",
- "$$ \\dot{\\phi} = \\omega$$\n",
- "\n",
- "\n",
- "So, the motion model is\n",
- "\n",
- "$$\\textbf{x}_{t+1} = F\\textbf{x}_t+B\\textbf{u}_t$$\n",
- "\n",
- "where\n",
- "\n",
- "$\\begin{equation*}\n",
- "F=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 & 0\\\\\n",
- "0 & 1 & 0 & 0\\\\\n",
- "0 & 0 & 1 & 0 \\\\\n",
- "0 & 0 & 0 & 0 \\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "B=\n",
- "\\begin{bmatrix}\n",
- "cos(\\phi)dt & 0\\\\\n",
- "sin(\\phi)dt & 0\\\\\n",
- "0 & dt\\\\\n",
- "1 & 0\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$dt$ is a time interval.\n",
- "\n",
- "This is implemented at [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L53-L67)\n",
- "\n",
- "Its Jacobian matrix is\n",
- "\n",
- "$\\begin{equation*}\n",
- "J_F=\n",
- "\\begin{bmatrix}\n",
- "\\frac{dx}{dx}& \\frac{dx}{dy} & \\frac{dx}{d\\phi} & \\frac{dx}{dv}\\\\\n",
- "\\frac{dy}{dx}& \\frac{dy}{dy} & \\frac{dy}{d\\phi} & \\frac{dy}{dv}\\\\\n",
- "\\frac{d\\phi}{dx}& \\frac{d\\phi}{dy} & \\frac{d\\phi}{d\\phi} & \\frac{d\\phi}{dv}\\\\\n",
- "\\frac{dv}{dx}& \\frac{dv}{dy} & \\frac{dv}{d\\phi} & \\frac{dv}{dv}\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- " =\n",
- "\\begin{bmatrix}\n",
- "1& 0 & -v sin(\\phi)dt & cos(\\phi)dt\\\\\n",
- "0 & 1 & v cos(\\phi)dt & sin(\\phi) dt\\\\\n",
- "0 & 0 & 1 & 0\\\\\n",
- "0 & 0 & 0 & 1\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Observation Model\n",
- "\n",
- "The robot can get x-y position infomation from GPS.\n",
- "\n",
- "So GPS Observation model is\n",
- "\n",
- "$$\\textbf{z}_{t} = H\\textbf{x}_t$$\n",
- "\n",
- "where\n",
- "\n",
- "$\\begin{equation*}\n",
- "B=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0& 0\\\\\n",
- "0 & 1 & 0& 0\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "Its Jacobian matrix is\n",
- "\n",
- "$\\begin{equation*}\n",
- "J_H=\n",
- "\\begin{bmatrix}\n",
- "\\frac{dx}{dx}& \\frac{dx}{dy} & \\frac{dx}{d\\phi} & \\frac{dx}{dv}\\\\\n",
- "\\frac{dy}{dx}& \\frac{dy}{dy} & \\frac{dy}{d\\phi} & \\frac{dy}{dv}\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- " =\n",
- "\\begin{bmatrix}\n",
- "1& 0 & 0 & 0\\\\\n",
- "0 & 1 & 0 & 0\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Extented Kalman Filter\n",
- "\n",
- "Localization process using Extendted Kalman Filter:EKF is\n",
- "\n",
- "=== Predict ===\n",
- "\n",
- "$x_{Pred} = Fx_t+Bu_t$\n",
- "\n",
- "$P_{Pred} = J_FP_t J_F^T + Q$\n",
- "\n",
- "=== Update ===\n",
- "\n",
- "$z_{Pred} = Hx_{Pred}$ \n",
- "\n",
- "$y = z - z_{Pred}$\n",
- "\n",
- "$S = J_H P_{Pred}.J_H^T + R$\n",
- "\n",
- "$K = P_{Pred}.J_H^T S^{-1}$\n",
- "\n",
- "$x_{t+1} = x_{Pred} + Ky$\n",
- "\n",
- "$P_{t+1} = ( I - K J_H) P_{Pred}$\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Ref:\n",
- "\n",
- "- [PROBABILISTIC\\-ROBOTICS\\.ORG](http://www.probabilistic-robotics.org/)"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.8"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py
index 1e43fee850..17cfc2e14c 100644
--- a/Localization/histogram_filter/histogram_filter.py
+++ b/Localization/histogram_filter/histogram_filter.py
@@ -11,15 +11,17 @@
"""
+import copy
import math
-import numpy as np
+
import matplotlib.pyplot as plt
-import copy
-from scipy.stats import norm
+import matplotlib as mpl
+import numpy as np
from scipy.ndimage import gaussian_filter
+from scipy.stats import norm
# Parameters
-EXTEND_AREA = 10.0 # [m] grid map extention length
+EXTEND_AREA = 10.0 # [m] grid map extended length
SIM_TIME = 50.0 # simulation time [s]
DT = 0.1 # time tick [s]
MAX_RANGE = 10.0 # maximum observation range
@@ -27,79 +29,74 @@
RANGE_STD = 3.0 # standard deviation for observation gaussian distribution
# grid map param
-XY_RESO = 0.5 # xy grid resolution
-MINX = -15.0
-MINY = -5.0
-MAXX = 15.0
-MAXY = 25.0
+XY_RESOLUTION = 0.5 # xy grid resolution
+MIN_X = -15.0
+MIN_Y = -5.0
+MAX_X = 15.0
+MAX_Y = 25.0
-# simulation paramters
+# simulation parameters
NOISE_RANGE = 2.0 # [m] 1σ range noise parameter
NOISE_SPEED = 0.5 # [m/s] 1σ speed noise parameter
-
show_animation = True
-class grid_map():
+class GridMap:
def __init__(self):
self.data = None
- self.xyreso = None
- self.minx = None
- self.miny = None
- self.maxx = None
- self.maxx = None
- self.xw = None
- self.yw = None
+ self.xy_resolution = None
+ self.min_x = None
+ self.min_y = None
+ self.max_x = None
+ self.max_y = None
+ self.x_w = None
+ self.y_w = None
self.dx = 0.0 # movement distance
self.dy = 0.0 # movement distance
-def histogram_filter_localization(gmap, u, z, yaw):
-
- gmap = motion_update(gmap, u, yaw)
+def histogram_filter_localization(grid_map, u, z, yaw):
+ grid_map = motion_update(grid_map, u, yaw)
- gmap = observation_update(gmap, z, RANGE_STD)
+ grid_map = observation_update(grid_map, z, RANGE_STD)
- return gmap
+ return grid_map
-def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std):
-
+def calc_gaussian_observation_pdf(grid_map, z, iz, ix, iy, std):
# predicted range
- x = ix * gmap.xyreso + gmap.minx
- y = iy * gmap.xyreso + gmap.miny
- d = math.sqrt((x - z[iz, 1])**2 + (y - z[iz, 2])**2)
+ x = ix * grid_map.xy_resolution + grid_map.min_x
+ y = iy * grid_map.xy_resolution + grid_map.min_y
+ d = math.hypot(x - z[iz, 1], y - z[iz, 2])
# likelihood
- pdf = (1.0 - norm.cdf(abs(d - z[iz, 0]), 0.0, std))
+ pdf = norm.pdf(d - z[iz, 0], 0.0, std)
return pdf
-def observation_update(gmap, z, std):
-
+def observation_update(grid_map, z, std):
for iz in range(z.shape[0]):
- for ix in range(gmap.xw):
- for iy in range(gmap.yw):
- gmap.data[ix][iy] *= calc_gaussian_observation_pdf(
- gmap, z, iz, ix, iy, std)
+ for ix in range(grid_map.x_w):
+ for iy in range(grid_map.y_w):
+ grid_map.data[ix][iy] *= calc_gaussian_observation_pdf(
+ grid_map, z, iz, ix, iy, std)
- gmap = normalize_probability(gmap)
+ grid_map = normalize_probability(grid_map)
- return gmap
+ return grid_map
-def calc_input():
+def calc_control_input():
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
- u = np.array([v, yawrate]).reshape(2, 1)
+ yaw_rate = 0.1 # [rad/s]
+ u = np.array([v, yaw_rate]).reshape(2, 1)
return u
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0, 0],
[0, 1.0, 0, 0],
[0, 0, 1.0, 0],
@@ -115,14 +112,14 @@ def motion_model(x, u):
return x
-def draw_heatmap(data, mx, my):
- maxp = max([max(igmap) for igmap in data])
- plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.Blues)
+def draw_heat_map(data, mx, my):
+ max_value = max([max(i_data) for i_data in data])
+ plt.grid(False)
+ plt.pcolor(mx, my, data, vmax=max_value, cmap=mpl.colormaps["Blues"])
plt.axis("equal")
def observation(xTrue, u, RFID):
-
xTrue = motion_model(xTrue, u)
z = np.zeros((0, 3))
@@ -131,7 +128,7 @@ def observation(xTrue, u, RFID):
dx = xTrue[0, 0] - RFID[i, 0]
dy = xTrue[1, 0] - RFID[i, 1]
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
if d <= MAX_RANGE:
# add noise to range observation
dn = d + np.random.randn() * NOISE_RANGE
@@ -145,71 +142,76 @@ def observation(xTrue, u, RFID):
return xTrue, z, ud
-def normalize_probability(gmap):
-
- sump = sum([sum(igmap) for igmap in gmap.data])
-
- for ix in range(gmap.xw):
- for iy in range(gmap.yw):
- gmap.data[ix][iy] /= sump
-
- return gmap
-
+def normalize_probability(grid_map):
+ sump = sum([sum(i_data) for i_data in grid_map.data])
-def init_gmap(xyreso, minx, miny, maxx, maxy):
+ for ix in range(grid_map.x_w):
+ for iy in range(grid_map.y_w):
+ grid_map.data[ix][iy] /= sump
- gmap = grid_map()
+ return grid_map
- gmap.xyreso = xyreso
- gmap.minx = minx
- gmap.miny = miny
- gmap.maxx = maxx
- gmap.maxy = maxy
- gmap.xw = int(round((gmap.maxx - gmap.minx) / gmap.xyreso))
- gmap.yw = int(round((gmap.maxy - gmap.miny) / gmap.xyreso))
- gmap.data = [[1.0 for i in range(gmap.yw)] for i in range(gmap.xw)]
- gmap = normalize_probability(gmap)
+def init_grid_map(xy_resolution, min_x, min_y, max_x, max_y):
+ grid_map = GridMap()
- return gmap
+ grid_map.xy_resolution = xy_resolution
+ grid_map.min_x = min_x
+ grid_map.min_y = min_y
+ grid_map.max_x = max_x
+ grid_map.max_y = max_y
+ grid_map.x_w = int(round((grid_map.max_x - grid_map.min_x)
+ / grid_map.xy_resolution))
+ grid_map.y_w = int(round((grid_map.max_y - grid_map.min_y)
+ / grid_map.xy_resolution))
+ grid_map.data = [[1.0 for _ in range(grid_map.y_w)]
+ for _ in range(grid_map.x_w)]
+ grid_map = normalize_probability(grid_map)
-def map_shift(gmap, xshift, yshift):
+ return grid_map
- tgmap = copy.deepcopy(gmap.data)
- for ix in range(gmap.xw):
- for iy in range(gmap.yw):
- nix = ix + xshift
- niy = iy + yshift
+def map_shift(grid_map, x_shift, y_shift):
+ tmp_grid_map = copy.deepcopy(grid_map.data)
- if nix >= 0 and nix < gmap.xw and niy >= 0 and niy < gmap.yw:
- gmap.data[ix + xshift][iy + yshift] = tgmap[ix][iy]
+ for ix in range(grid_map.x_w):
+ for iy in range(grid_map.y_w):
+ nix = ix + x_shift
+ niy = iy + y_shift
- return gmap
+ if 0 <= nix < grid_map.x_w and 0 <= niy < grid_map.y_w:
+ grid_map.data[ix + x_shift][iy + y_shift] =\
+ tmp_grid_map[ix][iy]
+ return grid_map
-def motion_update(gmap, u, yaw):
- gmap.dx += DT * math.cos(yaw) * u[0]
- gmap.dy += DT * math.sin(yaw) * u[0]
+def motion_update(grid_map, u, yaw):
+ grid_map.dx += DT * math.cos(yaw) * u[0]
+ grid_map.dy += DT * math.sin(yaw) * u[0]
- xshift = gmap.dx // gmap.xyreso
- yshift = gmap.dy // gmap.xyreso
+ x_shift = grid_map.dx // grid_map.xy_resolution
+ y_shift = grid_map.dy // grid_map.xy_resolution
- if abs(xshift) >= 1.0 or abs(yshift) >= 1.0: # map should be shifted
- gmap = map_shift(gmap, int(xshift), int(yshift))
- gmap.dx -= xshift * gmap.xyreso
- gmap.dy -= yshift * gmap.xyreso
+ if abs(x_shift) >= 1.0 or abs(y_shift) >= 1.0: # map should be shifted
+ grid_map = map_shift(grid_map, int(x_shift[0]), int(y_shift[0]))
+ grid_map.dx -= x_shift * grid_map.xy_resolution
+ grid_map.dy -= y_shift * grid_map.xy_resolution
- gmap.data = gaussian_filter(gmap.data, sigma=MOTION_STD)
+ # Add motion noise
+ grid_map.data = gaussian_filter(grid_map.data, sigma=MOTION_STD)
- return gmap
+ return grid_map
-def calc_grid_index(gmap):
- mx, my = np.mgrid[slice(gmap.minx - gmap.xyreso / 2.0, gmap.maxx + gmap.xyreso / 2.0, gmap.xyreso),
- slice(gmap.miny - gmap.xyreso / 2.0, gmap.maxy + gmap.xyreso / 2.0, gmap.xyreso)]
+def calc_grid_index(grid_map):
+ mx, my = np.mgrid[slice(grid_map.min_x - grid_map.xy_resolution / 2.0,
+ grid_map.max_x + grid_map.xy_resolution / 2.0,
+ grid_map.xy_resolution),
+ slice(grid_map.min_y - grid_map.xy_resolution / 2.0,
+ grid_map.max_y + grid_map.xy_resolution / 2.0,
+ grid_map.xy_resolution)]
return mx, my
@@ -217,37 +219,42 @@ def calc_grid_index(gmap):
def main():
print(__file__ + " start!!")
- # RFID positions [x, y]
- RFID = np.array([[10.0, 0.0],
- [10.0, 10.0],
- [0.0, 15.0],
- [-5.0, 20.0]])
+ # RF_ID positions [x, y]
+ RF_ID = np.array([[10.0, 0.0],
+ [10.0, 10.0],
+ [0.0, 15.0],
+ [-5.0, 20.0]])
time = 0.0
xTrue = np.zeros((4, 1))
- gmap = init_gmap(XY_RESO, MINX, MINY, MAXX, MAXY)
- mx, my = calc_grid_index(gmap) # for grid map visualization
+ grid_map = init_grid_map(XY_RESOLUTION, MIN_X, MIN_Y, MAX_X, MAX_Y)
+ mx, my = calc_grid_index(grid_map) # for grid map visualization
while SIM_TIME >= time:
time += DT
- print("Time:", time)
+ print(f"{time=:.1f}")
- u = calc_input()
+ u = calc_control_input()
yaw = xTrue[2, 0] # Orientation is known
- xTrue, z, ud = observation(xTrue, u, RFID)
+ xTrue, z, ud = observation(xTrue, u, RF_ID)
- gmap = histogram_filter_localization(gmap, u, z, yaw)
+ grid_map = histogram_filter_localization(grid_map, u, z, yaw)
if show_animation:
plt.cla()
- draw_heatmap(gmap.data, mx, my)
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ draw_heat_map(grid_map.data, mx, my)
plt.plot(xTrue[0, :], xTrue[1, :], "xr")
- plt.plot(RFID[:, 0], RFID[:, 1], ".k")
+ plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k")
for i in range(z.shape[0]):
- plt.plot([xTrue[0, :], z[i, 1]], [
- xTrue[1, :], z[i, 2]], "-k")
+ plt.plot([xTrue[0, 0], z[i, 1]],
+ [xTrue[1, 0], z[i, 2]],
+ "-k")
plt.title("Time[s]:" + str(time)[0: 4])
plt.pause(0.1)
diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py
index 8e93893e48..ba54a3d12b 100644
--- a/Localization/particle_filter/particle_filter.py
+++ b/Localization/particle_filter/particle_filter.py
@@ -5,18 +5,24 @@
author: Atsushi Sakai (@Atsushi_twi)
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
-import numpy as np
import math
+
import matplotlib.pyplot as plt
+import numpy as np
+
+from utils.angle import rot_mat_2d
# Estimation parameter of PF
-Q = np.diag([0.1])**2 # range error
-R = np.diag([1.0, np.deg2rad(40.0)])**2 # input error
+Q = np.diag([0.2]) ** 2 # range error
+R = np.diag([2.0, np.deg2rad(40.0)]) ** 2 # input error
# Simulation parameter
-Qsim = np.diag([0.2])**2
-Rsim = np.diag([1.0, np.deg2rad(30.0)])**2
+Q_sim = np.diag([0.2]) ** 2
+R_sim = np.diag([1.0, np.deg2rad(30.0)]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
@@ -31,40 +37,38 @@
def calc_input():
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
- u = np.array([[v, yawrate]]).T
+ yaw_rate = 0.1 # [rad/s]
+ u = np.array([[v, yaw_rate]]).T
return u
-def observation(xTrue, xd, u, RFID):
-
- xTrue = motion_model(xTrue, u)
+def observation(x_true, xd, u, rf_id):
+ x_true = motion_model(x_true, u)
# add noise to gps x-y
z = np.zeros((0, 3))
- for i in range(len(RFID[:, 0])):
+ for i in range(len(rf_id[:, 0])):
- dx = xTrue[0, 0] - RFID[i, 0]
- dy = xTrue[1, 0] - RFID[i, 1]
- d = math.sqrt(dx**2 + dy**2)
+ dx = x_true[0, 0] - rf_id[i, 0]
+ dy = x_true[1, 0] - rf_id[i, 1]
+ d = math.hypot(dx, dy)
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- zi = np.array([[dn, RFID[i, 0], RFID[i, 1]]])
+ dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise
+ zi = np.array([[dn, rf_id[i, 0], rf_id[i, 1]]])
z = np.vstack((z, zi))
# add noise to input
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
+ ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5
+ ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5
ud = np.array([[ud1, ud2]]).T
xd = motion_model(xd, ud)
- return xTrue, z, xd, ud
+ return x_true, z, xd, ud
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0, 0],
[0, 1.0, 0, 0],
[0, 0, 1.0, 0],
@@ -87,17 +91,22 @@ def gauss_likelihood(x, sigma):
return p
-def calc_covariance(xEst, px, pw):
- cov = np.zeros((3, 3))
-
- for i in range(px.shape[1]):
- dx = (px[:, i] - xEst)[0:3]
- cov += pw[0, i] * dx.dot(dx.T)
+def calc_covariance(x_est, px, pw):
+ """
+ calculate covariance matrix
+ see ipynb doc
+ """
+ cov = np.zeros((4, 4))
+ n_particle = px.shape[1]
+ for i in range(n_particle):
+ dx = (px[:, i:i + 1] - x_est)
+ cov += pw[0, i] * dx @ dx.T
+ cov *= 1.0 / (1.0 - pw @ pw.T)
return cov
-def pf_localization(px, pw, xEst, PEst, z, u):
+def pf_localization(px, pw, z, u):
"""
Localization with Particle filter
"""
@@ -105,9 +114,10 @@ def pf_localization(px, pw, xEst, PEst, z, u):
for ip in range(NP):
x = np.array([px[:, ip]]).T
w = pw[0, ip]
+
# Predict with random input sampling
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
+ ud1 = u[0, 0] + np.random.randn() * R[0, 0] ** 0.5
+ ud2 = u[1, 0] + np.random.randn() * R[1, 1] ** 0.5
ud = np.array([[ud1, ud2]]).T
x = motion_model(x, ud)
@@ -115,8 +125,8 @@ def pf_localization(px, pw, xEst, PEst, z, u):
for i in range(len(z[:, 0])):
dx = x[0, 0] - z[i, 1]
dy = x[1, 0] - z[i, 2]
- prez = math.sqrt(dx**2 + dy**2)
- dz = prez - z[i, 0]
+ pre_z = math.hypot(dx, dy)
+ dz = pre_z - z[i, 0]
w = w * gauss_likelihood(dz, math.sqrt(Q[0, 0]))
px[:, ip] = x[:, 0]
@@ -124,71 +134,68 @@ def pf_localization(px, pw, xEst, PEst, z, u):
pw = pw / pw.sum() # normalize
- xEst = px.dot(pw.T)
- PEst = calc_covariance(xEst, px, pw)
+ x_est = px.dot(pw.T)
+ p_est = calc_covariance(x_est, px, pw)
- px, pw = resampling(px, pw)
+ N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number
+ if N_eff < NTh:
+ px, pw = re_sampling(px, pw)
+ return x_est, p_est, px, pw
- return xEst, PEst, px, pw
-
-def resampling(px, pw):
+def re_sampling(px, pw):
"""
low variance re-sampling
"""
- Neff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number
- if Neff < NTh:
- wcum = np.cumsum(pw)
- base = np.cumsum(pw * 0.0 + 1 / NP) - 1 / NP
- resampleid = base + np.random.rand(base.shape[0]) / NP
-
- inds = []
- ind = 0
- for ip in range(NP):
- while resampleid[ip] > wcum[ind]:
- ind += 1
- inds.append(ind)
+ w_cum = np.cumsum(pw)
+ base = np.arange(0.0, 1.0, 1 / NP)
+ re_sample_id = base + np.random.uniform(0, 1 / NP)
+ indexes = []
+ ind = 0
+ for ip in range(NP):
+ while re_sample_id[ip] > w_cum[ind]:
+ ind += 1
+ indexes.append(ind)
- px = px[:, inds]
- pw = np.zeros((1, NP)) + 1.0 / NP # init weight
+ px = px[:, indexes]
+ pw = np.zeros((1, NP)) + 1.0 / NP # init weight
return px, pw
-def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
- Pxy = PEst[0:2, 0:2]
- eigval, eigvec = np.linalg.eig(Pxy)
+def plot_covariance_ellipse(x_est, p_est): # pragma: no cover
+ p_xy = p_est[0:2, 0:2]
+ eig_val, eig_vec = np.linalg.eig(p_xy)
- if eigval[0] >= eigval[1]:
- bigind = 0
- smallind = 1
+ if eig_val[0] >= eig_val[1]:
+ big_ind = 0
+ small_ind = 1
else:
- bigind = 1
- smallind = 0
+ big_ind = 1
+ small_ind = 0
t = np.arange(0, 2 * math.pi + 0.1, 0.1)
- # eigval[bigind] or eiqval[smallind] were occassionally negative numbers extremely
- # close to 0 (~10^-20), catch these cases and set the respective variable to 0
+ # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative
+ # numbers extremely close to 0 (~10^-20), catch these cases and set the
+ # respective variable to 0
try:
- a = math.sqrt(eigval[bigind])
+ a = math.sqrt(eig_val[big_ind])
except ValueError:
a = 0
try:
- b = math.sqrt(eigval[smallind])
+ b = math.sqrt(eig_val[small_ind])
except ValueError:
b = 0
x = [a * math.cos(it) for it in t]
y = [b * math.sin(it) for it in t]
- angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
- R = np.array([[math.cos(angle), math.sin(angle)],
- [-math.sin(angle), math.cos(angle)]])
- fx = R.dot(np.array([[x, y]]))
- px = np.array(fx[0, :] + xEst[0, 0]).flatten()
- py = np.array(fx[1, :] + xEst[1, 0]).flatten()
+ angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind])
+ fx = rot_mat_2d(angle) @ np.array([[x, y]])
+ px = np.array(fx[:, 0] + x_est[0, 0]).flatten()
+ py = np.array(fx[:, 1] + x_est[1, 0]).flatten()
plt.plot(px, py, "--r")
@@ -197,53 +204,56 @@ def main():
time = 0.0
- # RFID positions [x, y]
- RFID = np.array([[10.0, 0.0],
- [10.0, 10.0],
- [0.0, 15.0],
- [-5.0, 20.0]])
+ # RF_ID positions [x, y]
+ rf_id = np.array([[10.0, 0.0],
+ [10.0, 10.0],
+ [0.0, 15.0],
+ [-5.0, 20.0]])
# State Vector [x y yaw v]'
- xEst = np.zeros((4, 1))
- xTrue = np.zeros((4, 1))
- PEst = np.eye(4)
+ x_est = np.zeros((4, 1))
+ x_true = np.zeros((4, 1))
px = np.zeros((4, NP)) # Particle store
pw = np.zeros((1, NP)) + 1.0 / NP # Particle weight
- xDR = np.zeros((4, 1)) # Dead reckoning
+ x_dr = np.zeros((4, 1)) # Dead reckoning
# history
- hxEst = xEst
- hxTrue = xTrue
- hxDR = xTrue
+ h_x_est = x_est
+ h_x_true = x_true
+ h_x_dr = x_true
while SIM_TIME >= time:
time += DT
u = calc_input()
- xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+ x_true, z, x_dr, ud = observation(x_true, x_dr, u, rf_id)
- xEst, PEst, px, pw = pf_localization(px, pw, xEst, PEst, z, ud)
+ x_est, PEst, px, pw = pf_localization(px, pw, z, ud)
# store data history
- hxEst = np.hstack((hxEst, xEst))
- hxDR = np.hstack((hxDR, xDR))
- hxTrue = np.hstack((hxTrue, xTrue))
+ h_x_est = np.hstack((h_x_est, x_est))
+ h_x_dr = np.hstack((h_x_dr, x_dr))
+ h_x_true = np.hstack((h_x_true, x_true))
if show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
for i in range(len(z[:, 0])):
- plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k")
- plt.plot(RFID[:, 0], RFID[:, 1], "*k")
+ plt.plot([x_true[0, 0], z[i, 1]], [x_true[1, 0], z[i, 2]], "-k")
+ plt.plot(rf_id[:, 0], rf_id[:, 1], "*k")
plt.plot(px[0, :], px[1, :], ".r")
- plt.plot(np.array(hxTrue[0, :]).flatten(),
- np.array(hxTrue[1, :]).flatten(), "-b")
- plt.plot(np.array(hxDR[0, :]).flatten(),
- np.array(hxDR[1, :]).flatten(), "-k")
- plt.plot(np.array(hxEst[0, :]).flatten(),
- np.array(hxEst[1, :]).flatten(), "-r")
- plot_covariance_ellipse(xEst, PEst)
+ plt.plot(np.array(h_x_true[0, :]).flatten(),
+ np.array(h_x_true[1, :]).flatten(), "-b")
+ plt.plot(np.array(h_x_dr[0, :]).flatten(),
+ np.array(h_x_dr[1, :]).flatten(), "-k")
+ plt.plot(np.array(h_x_est[0, :]).flatten(),
+ np.array(h_x_est[1, :]).flatten(), "-r")
+ plot_covariance_ellipse(x_est, PEst)
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py
index 78b44754ee..4af748ec71 100644
--- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py
+++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py
@@ -6,23 +6,30 @@
"""
-import numpy as np
-import scipy.linalg
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
import math
+
import matplotlib.pyplot as plt
+import numpy as np
+import scipy.linalg
+
+from utils.angle import rot_mat_2d
# Covariance for UKF simulation
Q = np.diag([
- 0.1, # variance of location on x-axis
- 0.1, # variance of location on y-axis
- np.deg2rad(1.0), # variance of yaw angle
- 1.0 # variance of velocity
- ])**2 # predict state covariance
-R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance
+ 0.1, # variance of location on x-axis
+ 0.1, # variance of location on y-axis
+ np.deg2rad(1.0), # variance of yaw angle
+ 1.0 # variance of velocity
+]) ** 2 # predict state covariance
+R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance
# Simulation parameter
-INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2
-GPS_NOISE = np.diag([0.5, 0.5])**2
+INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2
+GPS_NOISE = np.diag([0.5, 0.5]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
@@ -43,7 +50,6 @@ def calc_input():
def observation(xTrue, xd, u):
-
xTrue = motion_model(xTrue, u)
# add noise to gps x-y
@@ -58,14 +64,13 @@ def observation(xTrue, xd, u):
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0, 0],
[0, 1.0, 0, 0],
[0, 0, 1.0, 0],
[0, 0, 0, 0]])
- B = np.array([[DT * math.cos(x[2]), 0],
- [DT * math.sin(x[2]), 0],
+ B = np.array([[DT * math.cos(x[2, 0]), 0],
+ [DT * math.sin(x[2, 0]), 0],
[0.0, DT],
[1.0, 0.0]])
@@ -144,7 +149,6 @@ def calc_pxz(sigma, x, z_sigma, zb, wc):
def ukf_estimation(xEst, PEst, z, u, wm, wc, gamma):
-
# Predict
sigma = generate_sigma_points(xEst, PEst, gamma)
sigma = predict_sigma_motion(sigma, u)
@@ -182,10 +186,8 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
b = math.sqrt(eigval[smallind])
x = [a * math.cos(it) for it in t]
y = [b * math.sin(it) for it in t]
- angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
- R = np.array([[math.cos(angle), math.sin(angle)],
- [-math.sin(angle), math.cos(angle)]])
- fx = R @ np.array([x, y])
+ angle = math.atan2(eigvec[1, bigind], eigvec[0, bigind])
+ fx = rot_mat_2d(angle) @ np.array([x, y])
px = np.array(fx[0, :] + xEst[0, 0]).flatten()
py = np.array(fx[1, :] + xEst[1, 0]).flatten()
plt.plot(px, py, "--r")
@@ -242,6 +244,9 @@ def main():
if show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(hz[0, :], hz[1, :], ".g")
plt.plot(np.array(hxTrue[0, :]).flatten(),
np.array(hxTrue[1, :]).flatten(), "-b")
diff --git a/Mapping/DistanceMap/distance_map.py b/Mapping/DistanceMap/distance_map.py
new file mode 100644
index 0000000000..0f96c9e8c6
--- /dev/null
+++ b/Mapping/DistanceMap/distance_map.py
@@ -0,0 +1,202 @@
+"""
+Distance Map
+
+author: Wang Zheng (@Aglargil)
+
+Reference:
+
+- [Distance Map]
+(https://cs.brown.edu/people/pfelzens/papers/dt-final.pdf)
+"""
+
+import numpy as np
+import matplotlib.pyplot as plt
+import scipy
+
+INF = 1e20
+ENABLE_PLOT = True
+
+
+def compute_sdf_scipy(obstacles):
+ """
+ Compute the signed distance field (SDF) from a boolean field using scipy.
+ This function has the same functionality as compute_sdf.
+ However, by using scipy.ndimage.distance_transform_edt, it can compute much faster.
+
+ Example: 500×500 map
+ • compute_sdf: 3 sec
+ • compute_sdf_scipy: 0.05 sec
+
+ Parameters
+ ----------
+ obstacles : array_like
+ A 2D boolean array where '1' represents obstacles and '0' represents free space.
+
+ Returns
+ -------
+ array_like
+ A 2D array representing the signed distance field, where positive values indicate distance
+ to the nearest obstacle, and negative values indicate distance to the nearest free space.
+ """
+ # distance_transform_edt use '0' as obstacles, so we need to convert the obstacles to '0'
+ a = scipy.ndimage.distance_transform_edt(obstacles == 0)
+ b = scipy.ndimage.distance_transform_edt(obstacles == 1)
+ return a - b
+
+
+def compute_udf_scipy(obstacles):
+ """
+ Compute the unsigned distance field (UDF) from a boolean field using scipy.
+ This function has the same functionality as compute_udf.
+ However, by using scipy.ndimage.distance_transform_edt, it can compute much faster.
+
+ Example: 500×500 map
+ • compute_udf: 1.5 sec
+ • compute_udf_scipy: 0.02 sec
+
+ Parameters
+ ----------
+ obstacles : array_like
+ A 2D boolean array where '1' represents obstacles and '0' represents free space.
+
+ Returns
+ -------
+ array_like
+ A 2D array of distances from the nearest obstacle, with the same dimensions as `bool_field`.
+ """
+ return scipy.ndimage.distance_transform_edt(obstacles == 0)
+
+
+def compute_sdf(obstacles):
+ """
+ Compute the signed distance field (SDF) from a boolean field.
+
+ Parameters
+ ----------
+ obstacles : array_like
+ A 2D boolean array where '1' represents obstacles and '0' represents free space.
+
+ Returns
+ -------
+ array_like
+ A 2D array representing the signed distance field, where positive values indicate distance
+ to the nearest obstacle, and negative values indicate distance to the nearest free space.
+ """
+ a = compute_udf(obstacles)
+ b = compute_udf(obstacles == 0)
+ return a - b
+
+
+def compute_udf(obstacles):
+ """
+ Compute the unsigned distance field (UDF) from a boolean field.
+
+ Parameters
+ ----------
+ obstacles : array_like
+ A 2D boolean array where '1' represents obstacles and '0' represents free space.
+
+ Returns
+ -------
+ array_like
+ A 2D array of distances from the nearest obstacle, with the same dimensions as `bool_field`.
+ """
+ edt = obstacles.copy()
+ if not np.all(np.isin(edt, [0, 1])):
+ raise ValueError("Input array should only contain 0 and 1")
+ edt = np.where(edt == 0, INF, edt)
+ edt = np.where(edt == 1, 0, edt)
+ for row in range(len(edt)):
+ dt(edt[row])
+ edt = edt.T
+ for row in range(len(edt)):
+ dt(edt[row])
+ edt = edt.T
+ return np.sqrt(edt)
+
+
+def dt(d):
+ """
+ Compute 1D distance transform under the squared Euclidean distance
+
+ Parameters
+ ----------
+ d : array_like
+ Input array containing the distances.
+
+ Returns:
+ --------
+ d : array_like
+ The transformed array with computed distances.
+ """
+ v = np.zeros(len(d) + 1)
+ z = np.zeros(len(d) + 1)
+ k = 0
+ v[0] = 0
+ z[0] = -INF
+ z[1] = INF
+ for q in range(1, len(d)):
+ s = ((d[q] + q * q) - (d[int(v[k])] + v[k] * v[k])) / (2 * q - 2 * v[k])
+ while s <= z[k]:
+ k = k - 1
+ s = ((d[q] + q * q) - (d[int(v[k])] + v[k] * v[k])) / (2 * q - 2 * v[k])
+ k = k + 1
+ v[k] = q
+ z[k] = s
+ z[k + 1] = INF
+ k = 0
+ for q in range(len(d)):
+ while z[k + 1] < q:
+ k = k + 1
+ dx = q - v[k]
+ d[q] = dx * dx + d[int(v[k])]
+
+
+def main():
+ obstacles = np.array(
+ [
+ [1, 0, 0, 0, 0],
+ [0, 1, 1, 1, 0],
+ [0, 1, 1, 1, 0],
+ [0, 0, 1, 1, 0],
+ [0, 0, 1, 0, 0],
+ [0, 0, 0, 0, 0],
+ [0, 0, 0, 0, 0],
+ [0, 0, 0, 0, 0],
+ [0, 0, 1, 0, 0],
+ [0, 0, 0, 0, 0],
+ [0, 0, 0, 0, 0],
+ ]
+ )
+
+ # Compute the signed distance field
+ sdf = compute_sdf(obstacles)
+ udf = compute_udf(obstacles)
+
+ if ENABLE_PLOT:
+ _, (ax1, ax2, ax3) = plt.subplots(1, 3, figsize=(15, 5))
+
+ obstacles_plot = ax1.imshow(obstacles, cmap="binary")
+ ax1.set_title("Obstacles")
+ ax1.set_xlabel("x")
+ ax1.set_ylabel("y")
+ plt.colorbar(obstacles_plot, ax=ax1)
+
+ udf_plot = ax2.imshow(udf, cmap="viridis")
+ ax2.set_title("Unsigned Distance Field")
+ ax2.set_xlabel("x")
+ ax2.set_ylabel("y")
+ plt.colorbar(udf_plot, ax=ax2)
+
+ sdf_plot = ax3.imshow(sdf, cmap="RdBu")
+ ax3.set_title("Signed Distance Field")
+ ax3.set_xlabel("x")
+ ax3.set_ylabel("y")
+ plt.colorbar(sdf_plot, ax=ax3)
+
+ plt.tight_layout()
+ plt.show()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/Mapping/__init__.py b/Mapping/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/Mapping/circle_fitting/circle_fitting.py b/Mapping/circle_fitting/circle_fitting.py
index dae9413d27..b5714b507c 100644
--- a/Mapping/circle_fitting/circle_fitting.py
+++ b/Mapping/circle_fitting/circle_fitting.py
@@ -16,12 +16,33 @@
def circle_fitting(x, y):
"""
- Circle Fitting with least squared
- input: point x-y positions
- output cxe x center position
- cye y center position
- re radius of circle
- error: prediction error
+ Fits a circle to a given set of points using a least-squares approach.
+
+ This function calculates the center (x, y) and radius of a circle that best fits
+ the given set of points in a two-dimensional plane. It minimizes the squared
+ errors between the circle and the provided points and returns the calculated
+ center coordinates, radius, and the fitting error.
+
+ Raises
+ ------
+ ValueError
+ If the input lists x and y do not contain the same number of elements.
+
+ Parameters
+ ----------
+ x : list[float]
+ The x-coordinates of the points.
+ y : list[float]
+ The y-coordinates of the points.
+
+ Returns
+ -------
+ tuple[float, float, float, float]
+ A tuple containing:
+ - The x-coordinate of the center of the fitted circle (float).
+ - The y-coordinate of the center of the fitted circle (float).
+ - The radius of the fitted circle (float).
+ - The fitting error as a deviation metric (float).
"""
sumx = sum(x)
@@ -40,9 +61,9 @@ def circle_fitting(x, y):
T = np.linalg.inv(F).dot(G)
- cxe = float(T[0] / -2)
- cye = float(T[1] / -2)
- re = math.sqrt(cxe**2 + cye**2 - T[2])
+ cxe = float(T[0, 0] / -2)
+ cye = float(T[1, 0] / -2)
+ re = math.sqrt(cxe**2 + cye**2 - T[2, 0])
error = sum([np.hypot(cxe - ix, cye - iy) - re for (ix, iy) in zip(x, y)])
@@ -124,6 +145,9 @@ def main():
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.axis("equal")
plt.plot(0.0, 0.0, "*r")
plot_circle(cx, cy, cr)
diff --git a/Mapping/gaussian_grid_map/gaussian_grid_map.py b/Mapping/gaussian_grid_map/gaussian_grid_map.py
index b520b63944..b7664f1acb 100644
--- a/Mapping/gaussian_grid_map/gaussian_grid_map.py
+++ b/Mapping/gaussian_grid_map/gaussian_grid_map.py
@@ -31,7 +31,7 @@ def generate_gaussian_grid_map(ox, oy, xyreso, std):
# Search minimum distance
mindis = float("inf")
for (iox, ioy) in zip(ox, oy):
- d = math.sqrt((iox - x)**2 + (ioy - y)**2)
+ d = math.hypot(iox - x, ioy - y)
if mindis >= d:
mindis = d
@@ -73,6 +73,9 @@ def main():
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
draw_heatmap(gmap, minx, maxx, miny, maxy, xyreso)
plt.plot(ox, oy, "xr")
plt.plot(0.0, 0.0, "ob")
diff --git a/Mapping/grid_map_lib/grid_map_lib.py b/Mapping/grid_map_lib/grid_map_lib.py
index ef94cb5e98..d08d8ec5ba 100644
--- a/Mapping/grid_map_lib/grid_map_lib.py
+++ b/Mapping/grid_map_lib/grid_map_lib.py
@@ -5,22 +5,42 @@
author: Atsushi Sakai
"""
-
+from functools import total_ordering
import matplotlib.pyplot as plt
import numpy as np
+@total_ordering
+class FloatGrid:
+
+ def __init__(self, init_val=0.0):
+ self.data = init_val
+
+ def get_float_data(self):
+ return self.data
+
+ def __eq__(self, other):
+ if not isinstance(other, FloatGrid):
+ return NotImplemented
+ return self.get_float_data() == other.get_float_data()
+
+ def __lt__(self, other):
+ if not isinstance(other, FloatGrid):
+ return NotImplemented
+ return self.get_float_data() < other.get_float_data()
+
+
class GridMap:
"""
GridMap class
"""
def __init__(self, width, height, resolution,
- center_x, center_y, init_val=0.0):
+ center_x, center_y, init_val=FloatGrid(0.0)):
"""__init__
:param width: number of grid for width
- :param height: number of grid for heigt
+ :param height: number of grid for height
:param resolution: grid resolution [m]
:param center_x: center x position [m]
:param center_y: center y position [m]
@@ -32,13 +52,12 @@ def __init__(self, width, height, resolution,
self.center_x = center_x
self.center_y = center_y
- self.left_lower_x = self.center_x - \
- (self.width / 2.0) * self.resolution
- self.left_lower_y = self.center_y - \
- (self.height / 2.0) * self.resolution
+ self.left_lower_x = self.center_x - self.width / 2.0 * self.resolution
+ self.left_lower_y = self.center_y - self.height / 2.0 * self.resolution
- self.ndata = self.width * self.height
- self.data = [init_val] * self.ndata
+ self.n_data = self.width * self.height
+ self.data = [init_val] * self.n_data
+ self.data_type = type(init_val)
def get_value_from_xy_index(self, x_ind, y_ind):
"""get_value_from_xy_index
@@ -51,7 +70,7 @@ def get_value_from_xy_index(self, x_ind, y_ind):
grid_ind = self.calc_grid_index_from_xy_index(x_ind, y_ind)
- if 0 <= grid_ind <= self.ndata:
+ if 0 <= grid_ind < self.n_data:
return self.data[grid_ind]
else:
return None
@@ -98,9 +117,12 @@ def set_value_from_xy_index(self, x_ind, y_ind, val):
:param val: grid value
"""
+ if (x_ind is None) or (y_ind is None):
+ return False, False
+
grid_ind = int(y_ind * self.width + x_ind)
- if 0 <= grid_ind <= self.ndata:
+ if 0 <= grid_ind < self.n_data and isinstance(val, self.data_type):
self.data[grid_ind] = val
return True # OK
else:
@@ -119,8 +141,8 @@ def set_value_from_polygon(self, pol_x, pol_y, val, inside=True):
# making ring polygon
if (pol_x[0] != pol_x[-1]) or (pol_y[0] != pol_y[-1]):
- pol_x.append(pol_x[0])
- pol_y.append(pol_y[0])
+ np.append(pol_x, pol_x[0])
+ np.append(pol_y, pol_y[0])
# setting value for all grid
for x_ind in range(self.width):
@@ -137,6 +159,27 @@ def calc_grid_index_from_xy_index(self, x_ind, y_ind):
grid_ind = int(y_ind * self.width + x_ind)
return grid_ind
+ def calc_xy_index_from_grid_index(self, grid_ind):
+ y_ind, x_ind = divmod(grid_ind, self.width)
+ return x_ind, y_ind
+
+ def calc_grid_index_from_xy_pos(self, x_pos, y_pos):
+ """get_xy_index_from_xy_pos
+
+ :param x_pos: x position [m]
+ :param y_pos: y position [m]
+ """
+ x_ind = self.calc_xy_index_from_position(
+ x_pos, self.left_lower_x, self.width)
+ y_ind = self.calc_xy_index_from_position(
+ y_pos, self.left_lower_y, self.height)
+
+ return self.calc_grid_index_from_xy_index(x_ind, y_ind)
+
+ def calc_grid_central_xy_position_from_grid_index(self, grid_ind):
+ x_ind, y_ind = self.calc_xy_index_from_grid_index(grid_ind)
+ return self.calc_grid_central_xy_position_from_xy_index(x_ind, y_ind)
+
def calc_grid_central_xy_position_from_xy_index(self, x_ind, y_ind):
x_pos = self.calc_grid_central_xy_position_from_index(
x_ind, self.left_lower_x)
@@ -155,54 +198,82 @@ def calc_xy_index_from_position(self, pos, lower_pos, max_index):
else:
return None
- def check_occupied_from_xy_index(self, xind, yind, occupied_val=1.0):
+ def check_occupied_from_xy_index(self, x_ind, y_ind, occupied_val):
- val = self.get_value_from_xy_index(xind, yind)
+ val = self.get_value_from_xy_index(x_ind, y_ind)
- if val >= occupied_val:
+ if val is None or val >= occupied_val:
return True
else:
return False
+ def expand_grid(self, occupied_val=FloatGrid(1.0)):
+ x_inds, y_inds, values = [], [], []
+
+ for ix in range(self.width):
+ for iy in range(self.height):
+ if self.check_occupied_from_xy_index(ix, iy, occupied_val):
+ x_inds.append(ix)
+ y_inds.append(iy)
+ values.append(self.get_value_from_xy_index(ix, iy))
+
+ for (ix, iy, value) in zip(x_inds, y_inds, values):
+ self.set_value_from_xy_index(ix + 1, iy, val=value)
+ self.set_value_from_xy_index(ix, iy + 1, val=value)
+ self.set_value_from_xy_index(ix + 1, iy + 1, val=value)
+ self.set_value_from_xy_index(ix - 1, iy, val=value)
+ self.set_value_from_xy_index(ix, iy - 1, val=value)
+ self.set_value_from_xy_index(ix - 1, iy - 1, val=value)
+
@staticmethod
def check_inside_polygon(iox, ioy, x, y):
- npoint = len(x) - 1
+ n_point = len(x) - 1
inside = False
- for i1 in range(npoint):
- i2 = (i1 + 1) % (npoint + 1)
+ for i1 in range(n_point):
+ i2 = (i1 + 1) % (n_point + 1)
if x[i1] >= x[i2]:
min_x, max_x = x[i2], x[i1]
else:
min_x, max_x = x[i1], x[i2]
- if not min_x < iox < max_x:
+ if not min_x <= iox < max_x:
continue
- if (y[i1] + (y[i2] - y[i1]) / (x[i2] - x[i1])
- * (iox - x[i1]) - ioy) > 0.0:
+ tmp1 = (y[i2] - y[i1]) / (x[i2] - x[i1])
+ if (y[i1] + tmp1 * (iox - x[i1]) - ioy) > 0.0:
inside = not inside
return inside
- def plot_grid_map(self):
-
- grid_data = np.reshape(np.array(self.data), (self.height, self.width))
- fig, ax = plt.subplots()
+ def print_grid_map_info(self):
+ print("width:", self.width)
+ print("height:", self.height)
+ print("resolution:", self.resolution)
+ print("center_x:", self.center_x)
+ print("center_y:", self.center_y)
+ print("left_lower_x:", self.left_lower_x)
+ print("left_lower_y:", self.left_lower_y)
+ print("n_data:", self.n_data)
+
+ def plot_grid_map(self, ax=None):
+ float_data_array = np.array([d.get_float_data() for d in self.data])
+ grid_data = np.reshape(float_data_array, (self.height, self.width))
+ if not ax:
+ fig, ax = plt.subplots()
heat_map = ax.pcolor(grid_data, cmap="Blues", vmin=0.0, vmax=1.0)
plt.axis("equal")
- plt.show()
return heat_map
-def test_polygon_set():
- ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0]
- oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0]
+def polygon_set_demo():
+ ox = [0.0, 4.35, 20.0, 50.0, 100.0, 130.0, 40.0]
+ oy = [0.0, -4.15, -20.0, 0.0, 30.0, 60.0, 80.0]
grid_map = GridMap(600, 290, 0.7, 60.0, 30.5)
- grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False)
+ grid_map.set_value_from_polygon(ox, oy, FloatGrid(1.0), inside=False)
grid_map.plot_grid_map()
@@ -210,24 +281,27 @@ def test_polygon_set():
plt.grid(True)
-def test_position_set():
+def position_set_demo():
grid_map = GridMap(100, 120, 0.5, 10.0, -0.5)
- grid_map.set_value_from_xy_pos(10.1, -1.1, 1.0)
- grid_map.set_value_from_xy_pos(10.1, -0.1, 1.0)
- grid_map.set_value_from_xy_pos(10.1, 1.1, 1.0)
- grid_map.set_value_from_xy_pos(11.1, 0.1, 1.0)
- grid_map.set_value_from_xy_pos(10.1, 0.1, 1.0)
- grid_map.set_value_from_xy_pos(9.1, 0.1, 1.0)
+ grid_map.set_value_from_xy_pos(10.1, -1.1, FloatGrid(1.0))
+ grid_map.set_value_from_xy_pos(10.1, -0.1, FloatGrid(1.0))
+ grid_map.set_value_from_xy_pos(10.1, 1.1, FloatGrid(1.0))
+ grid_map.set_value_from_xy_pos(11.1, 0.1, FloatGrid(1.0))
+ grid_map.set_value_from_xy_pos(10.1, 0.1, FloatGrid(1.0))
+ grid_map.set_value_from_xy_pos(9.1, 0.1, FloatGrid(1.0))
grid_map.plot_grid_map()
+ plt.axis("equal")
+ plt.grid(True)
+
def main():
print("start!!")
- test_position_set()
- test_polygon_set()
+ position_set_demo()
+ polygon_set_demo()
plt.show()
diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py
index 8edfa11e3a..cee01e5ad5 100644
--- a/Mapping/kmeans_clustering/kmeans_clustering.py
+++ b/Mapping/kmeans_clustering/kmeans_clustering.py
@@ -6,97 +6,112 @@
"""
-import numpy as np
import math
import matplotlib.pyplot as plt
import random
+# k means parameters
+MAX_LOOP = 10
+DCOST_TH = 0.1
show_animation = True
-class Clusters:
-
- def __init__(self, x, y, nlabel):
- self.x = x
- self.y = y
- self.ndata = len(self.x)
- self.nlabel = nlabel
- self.labels = [random.randint(0, nlabel - 1)
- for _ in range(self.ndata)]
- self.cx = [0.0 for _ in range(nlabel)]
- self.cy = [0.0 for _ in range(nlabel)]
-
-
def kmeans_clustering(rx, ry, nc):
-
+ """
+ Performs k-means clustering on the given dataset, iteratively adjusting cluster centroids
+ until convergence within a defined threshold or reaching the maximum number of
+ iterations.
+
+ The implementation initializes clusters, calculates initial centroids, and refines the
+ clusters through iterative updates to optimize the cost function based on minimum
+ distance between datapoints and centroids.
+
+ Arguments:
+ rx: List[float]
+ The x-coordinates of the dataset points to be clustered.
+ ry: List[float]
+ The y-coordinates of the dataset points to be clustered.
+ nc: int
+ The number of clusters to group the data into.
+
+ Returns:
+ Clusters
+ An instance containing the final cluster assignments and centroids after
+ convergence.
+
+ Raises:
+ None
+
+ """
clusters = Clusters(rx, ry, nc)
- clusters = calc_centroid(clusters)
+ clusters.calc_centroid()
- MAX_LOOP = 10
- DCOST_TH = 0.1
- pcost = 100.0
+ pre_cost = float("inf")
for loop in range(MAX_LOOP):
- # print("Loop:", loop)
- clusters, cost = update_clusters(clusters)
- clusters = calc_centroid(clusters)
+ cost = clusters.update_clusters()
+ clusters.calc_centroid()
- dcost = abs(cost - pcost)
- if dcost < DCOST_TH:
+ d_cost = abs(cost - pre_cost)
+ if d_cost < DCOST_TH:
break
- pcost = cost
-
- return clusters
-
-
-def calc_centroid(clusters):
-
- for ic in range(clusters.nlabel):
- x, y = calc_labeled_points(ic, clusters)
- ndata = len(x)
- clusters.cx[ic] = sum(x) / ndata
- clusters.cy[ic] = sum(y) / ndata
+ pre_cost = cost
return clusters
-def update_clusters(clusters):
- cost = 0.0
-
- for ip in range(clusters.ndata):
- px = clusters.x[ip]
- py = clusters.y[ip]
-
- dx = [icx - px for icx in clusters.cx]
- dy = [icy - py for icy in clusters.cy]
-
- dlist = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)]
- mind = min(dlist)
- min_id = dlist.index(mind)
- clusters.labels[ip] = min_id
- cost += mind
-
- return clusters, cost
-
-
-def calc_labeled_points(ic, clusters):
-
- inds = np.array([i for i in range(clusters.ndata)
- if clusters.labels[i] == ic])
- tx = np.array(clusters.x)
- ty = np.array(clusters.y)
-
- x = tx[inds]
- y = ty[inds]
-
- return x, y
-
-
-def calc_raw_data(cx, cy, npoints, rand_d):
+class Clusters:
+ def __init__(self, x, y, n_label):
+ self.x = x
+ self.y = y
+ self.n_data = len(self.x)
+ self.n_label = n_label
+ self.labels = [random.randint(0, n_label - 1)
+ for _ in range(self.n_data)]
+ self.center_x = [0.0 for _ in range(n_label)]
+ self.center_y = [0.0 for _ in range(n_label)]
+
+ def plot_cluster(self):
+ for label in set(self.labels):
+ x, y = self._get_labeled_x_y(label)
+ plt.plot(x, y, ".")
+
+ def calc_centroid(self):
+ for label in set(self.labels):
+ x, y = self._get_labeled_x_y(label)
+ n_data = len(x)
+ self.center_x[label] = sum(x) / n_data
+ self.center_y[label] = sum(y) / n_data
+
+ def update_clusters(self):
+ cost = 0.0
+
+ for ip in range(self.n_data):
+ px = self.x[ip]
+ py = self.y[ip]
+
+ dx = [icx - px for icx in self.center_x]
+ dy = [icy - py for icy in self.center_y]
+
+ dist_list = [math.hypot(idx, idy) for (idx, idy) in zip(dx, dy)]
+ min_dist = min(dist_list)
+ min_id = dist_list.index(min_dist)
+ self.labels[ip] = min_id
+ cost += min_dist
+
+ return cost
+
+ def _get_labeled_x_y(self, target_label):
+ x = [self.x[i] for i, label in enumerate(self.labels) if label == target_label]
+ y = [self.y[i] for i, label in enumerate(self.labels) if label == target_label]
+ return x, y
+
+
+def calc_raw_data(cx, cy, n_points, rand_d):
rx, ry = [], []
for (icx, icy) in zip(cx, cy):
- for _ in range(npoints):
+ for _ in range(n_points):
rx.append(icx + rand_d * (random.random() - 0.5))
ry.append(icy + rand_d * (random.random() - 0.5))
@@ -104,48 +119,28 @@ def calc_raw_data(cx, cy, npoints, rand_d):
def update_positions(cx, cy):
-
+ # object moving parameters
DX1 = 0.4
DY1 = 0.5
-
- cx[0] += DX1
- cy[0] += DY1
-
DX2 = -0.3
DY2 = -0.5
+ cx[0] += DX1
+ cy[0] += DY1
cx[1] += DX2
cy[1] += DY2
return cx, cy
-def calc_association(cx, cy, clusters):
-
- inds = []
-
- for ic, _ in enumerate(cx):
- tcx = cx[ic]
- tcy = cy[ic]
-
- dx = [icx - tcx for icx in clusters.cx]
- dy = [icy - tcy for icy in clusters.cy]
-
- dlist = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)]
- min_id = dlist.index(min(dlist))
- inds.append(min_id)
-
- return inds
-
-
def main():
print(__file__ + " start!!")
cx = [0.0, 8.0]
cy = [0.0, 8.0]
- npoints = 10
+ n_points = 10
rand_d = 3.0
- ncluster = 2
+ n_cluster = 2
sim_time = 15.0
dt = 1.0
time = 0.0
@@ -154,20 +149,20 @@ def main():
print("Time:", time)
time += dt
- # simulate objects
+ # objects moving simulation
cx, cy = update_positions(cx, cy)
- rx, ry = calc_raw_data(cx, cy, npoints, rand_d)
+ raw_x, raw_y = calc_raw_data(cx, cy, n_points, rand_d)
- clusters = kmeans_clustering(rx, ry, ncluster)
+ clusters = kmeans_clustering(raw_x, raw_y, n_cluster)
# for animation
if show_animation: # pragma: no cover
plt.cla()
- inds = calc_association(cx, cy, clusters)
- for ic in inds:
- x, y = calc_labeled_points(ic, clusters)
- plt.plot(x, y, "x")
- plt.plot(cx, cy, "o")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ clusters.plot_cluster()
+ plt.plot(cx, cy, "or")
plt.xlim(-2.0, 10.0)
plt.ylim(-2.0, 10.0)
plt.pause(dt)
diff --git a/Mapping/lidar_to_grid_map/animation.gif b/Mapping/lidar_to_grid_map/animation.gif
deleted file mode 100644
index 210ff5817c..0000000000
Binary files a/Mapping/lidar_to_grid_map/animation.gif and /dev/null differ
diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py
index 60bf4db69c..ad987392f5 100644
--- a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py
+++ b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py
@@ -2,15 +2,16 @@
LIDAR to 2D grid map example
-author: Erno Horvath, Csaba Hajdu based on Atsushi Sakai's scripts (@Atsushi_twi)
+author: Erno Horvath, Csaba Hajdu based on Atsushi Sakai's scripts
"""
import math
-import numpy as np
-import matplotlib.pyplot as plt
from collections import deque
+import matplotlib.pyplot as plt
+import numpy as np
+
EXTEND_AREA = 1.0
@@ -18,7 +19,8 @@ def file_read(f):
"""
Reading LIDAR laser beams (angles and corresponding distance data)
"""
- measures = [line.split(",") for line in open(f)]
+ with open(f) as data:
+ measures = [line.split(",") for line in data]
angles = []
distances = []
for measure in measures:
@@ -44,47 +46,49 @@ def bresenham(start, end):
x2, y2 = end
dx = x2 - x1
dy = y2 - y1
- is_steep = abs(dy) > abs(dx) # determine how steep the line is
- if is_steep: # rotate line
+ is_steep = abs(dy) > abs(dx) # determine how steep the line is
+ if is_steep: # rotate line
x1, y1 = y1, x1
x2, y2 = y2, x2
- swapped = False # swap start and end points if necessary and store swap state
+ # swap start and end points if necessary and store swap state
+ swapped = False
if x1 > x2:
x1, x2 = x2, x1
y1, y2 = y2, y1
swapped = True
- dx = x2 - x1 # recalculate differentials
- dy = y2 - y1 # recalculate differentials
- error = int(dx / 2.0) # calculate error
- ystep = 1 if y1 < y2 else -1
+ dx = x2 - x1 # recalculate differentials
+ dy = y2 - y1 # recalculate differentials
+ error = int(dx / 2.0) # calculate error
+ y_step = 1 if y1 < y2 else -1
# iterate over bounding box generating points between start and end
y = y1
points = []
for x in range(x1, x2 + 1):
coord = [y, x] if is_steep else (x, y)
- points.append(coord)
+ points.append(coord)
error -= abs(dy)
if error < 0:
- y += ystep
+ y += y_step
error += dx
- if swapped: # reverse the list if the coordinates were swapped
+ if swapped: # reverse the list if the coordinates were swapped
points.reverse()
points = np.array(points)
return points
-def calc_grid_map_config(ox, oy, xyreso):
+def calc_grid_map_config(ox, oy, xy_resolution):
"""
- Calculates the size, and the maximum distances according to the the measurement center
+ Calculates the size, and the maximum distances according to the the
+ measurement center
"""
- minx = round(min(ox) - EXTEND_AREA / 2.0)
- miny = round(min(oy) - EXTEND_AREA / 2.0)
- maxx = round(max(ox) + EXTEND_AREA / 2.0)
- maxy = round(max(oy) + EXTEND_AREA / 2.0)
- xw = int(round((maxx - minx) / xyreso))
- yw = int(round((maxy - miny) / xyreso))
+ min_x = round(min(ox) - EXTEND_AREA / 2.0)
+ min_y = round(min(oy) - EXTEND_AREA / 2.0)
+ max_x = round(max(ox) + EXTEND_AREA / 2.0)
+ max_y = round(max(oy) + EXTEND_AREA / 2.0)
+ xw = int(round((max_x - min_x) / xy_resolution))
+ yw = int(round((max_y - min_y) / xy_resolution))
print("The grid map is ", xw, "x", yw, ".")
- return minx, miny, maxx, maxy, xw, yw
+ return min_x, min_y, max_x, max_y, xw, yw
def atan_zero_to_twopi(y, x):
@@ -94,96 +98,110 @@ def atan_zero_to_twopi(y, x):
return angle
-def init_floodfill(cpoint, opoints, xypoints, mincoord, xyreso):
+def init_flood_fill(center_point, obstacle_points, xy_points, min_coord,
+ xy_resolution):
"""
- cpoint: center point
- opoints: detected obstacles points (x,y)
- xypoints: (x,y) point pairs
+ center_point: center point
+ obstacle_points: detected obstacles points (x,y)
+ xy_points: (x,y) point pairs
"""
- centix, centiy = cpoint
- prev_ix, prev_iy = centix - 1, centiy
- ox, oy = opoints
- xw, yw = xypoints
- minx, miny = mincoord
- pmap = (np.ones((xw, yw))) * 0.5
+ center_x, center_y = center_point
+ prev_ix, prev_iy = center_x - 1, center_y
+ ox, oy = obstacle_points
+ xw, yw = xy_points
+ min_x, min_y = min_coord
+ occupancy_map = (np.ones((xw, yw))) * 0.5
for (x, y) in zip(ox, oy):
- ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area
- iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area
+ # x coordinate of the the occupied area
+ ix = int(round((x - min_x) / xy_resolution))
+ # y coordinate of the the occupied area
+ iy = int(round((y - min_y) / xy_resolution))
free_area = bresenham((prev_ix, prev_iy), (ix, iy))
for fa in free_area:
- pmap[fa[0]][fa[1]] = 0 # free area 0.0
+ occupancy_map[fa[0]][fa[1]] = 0 # free area 0.0
prev_ix = ix
prev_iy = iy
- return pmap
+ return occupancy_map
-def flood_fill(cpoint, pmap):
+def flood_fill(center_point, occupancy_map):
"""
- cpoint: starting point (x,y) of fill
- pmap: occupancy map generated from Bresenham ray-tracing
+ center_point: starting point (x,y) of fill
+ occupancy_map: occupancy map generated from Bresenham ray-tracing
"""
# Fill empty areas with queue method
- sx, sy = pmap.shape
+ sx, sy = occupancy_map.shape
fringe = deque()
- fringe.appendleft(cpoint)
+ fringe.appendleft(center_point)
while fringe:
n = fringe.pop()
nx, ny = n
# West
if nx > 0:
- if pmap[nx - 1, ny] == 0.5:
- pmap[nx - 1, ny] = 0.0
+ if occupancy_map[nx - 1, ny] == 0.5:
+ occupancy_map[nx - 1, ny] = 0.0
fringe.appendleft((nx - 1, ny))
# East
if nx < sx - 1:
- if pmap[nx + 1, ny] == 0.5:
- pmap[nx + 1, ny] = 0.0
+ if occupancy_map[nx + 1, ny] == 0.5:
+ occupancy_map[nx + 1, ny] = 0.0
fringe.appendleft((nx + 1, ny))
# North
if ny > 0:
- if pmap[nx, ny - 1] == 0.5:
- pmap[nx, ny - 1] = 0.0
+ if occupancy_map[nx, ny - 1] == 0.5:
+ occupancy_map[nx, ny - 1] = 0.0
fringe.appendleft((nx, ny - 1))
# South
if ny < sy - 1:
- if pmap[nx, ny + 1] == 0.5:
- pmap[nx, ny + 1] = 0.0
+ if occupancy_map[nx, ny + 1] == 0.5:
+ occupancy_map[nx, ny + 1] = 0.0
fringe.appendleft((nx, ny + 1))
-def generate_ray_casting_grid_map(ox, oy, xyreso, breshen=True):
+def generate_ray_casting_grid_map(ox, oy, xy_resolution, breshen=True):
"""
- The breshen boolean tells if it's computed with bresenham ray casting (True) or with flood fill (False)
+ The breshen boolean tells if it's computed with bresenham ray casting
+ (True) or with flood fill (False)
"""
- minx, miny, maxx, maxy, xw, yw = calc_grid_map_config(ox, oy, xyreso)
- pmap = np.ones((xw, yw))/2 # default 0.5 -- [[0.5 for i in range(yw)] for i in range(xw)]
- centix = int(round(-minx / xyreso)) # center x coordinate of the grid map
- centiy = int(round(-miny / xyreso)) # center y coordinate of the grid map
+ min_x, min_y, max_x, max_y, x_w, y_w = calc_grid_map_config(
+ ox, oy, xy_resolution)
+ # default 0.5 -- [[0.5 for i in range(y_w)] for i in range(x_w)]
+ occupancy_map = np.ones((x_w, y_w)) / 2
+ center_x = int(
+ round(-min_x / xy_resolution)) # center x coordinate of the grid map
+ center_y = int(
+ round(-min_y / xy_resolution)) # center y coordinate of the grid map
# occupancy grid computed with bresenham ray casting
if breshen:
for (x, y) in zip(ox, oy):
- ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area
- iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area
- laser_beams = bresenham((centix, centiy), (ix, iy)) # line form the lidar to the cooupied point
+ # x coordinate of the the occupied area
+ ix = int(round((x - min_x) / xy_resolution))
+ # y coordinate of the the occupied area
+ iy = int(round((y - min_y) / xy_resolution))
+ laser_beams = bresenham((center_x, center_y), (
+ ix, iy)) # line form the lidar to the occupied point
for laser_beam in laser_beams:
- pmap[laser_beam[0]][laser_beam[1]] = 0.0 # free area 0.0
- pmap[ix][iy] = 1.0 # occupied area 1.0
- pmap[ix+1][iy] = 1.0 # extend the occupied area
- pmap[ix][iy+1] = 1.0 # extend the occupied area
- pmap[ix+1][iy+1] = 1.0 # extend the occupied area
+ occupancy_map[laser_beam[0]][
+ laser_beam[1]] = 0.0 # free area 0.0
+ occupancy_map[ix][iy] = 1.0 # occupied area 1.0
+ occupancy_map[ix + 1][iy] = 1.0 # extend the occupied area
+ occupancy_map[ix][iy + 1] = 1.0 # extend the occupied area
+ occupancy_map[ix + 1][iy + 1] = 1.0 # extend the occupied area
# occupancy grid computed with with flood fill
else:
- pmap = init_floodfill((centix, centiy), (ox, oy), (xw, yw), (minx, miny), xyreso)
- flood_fill((centix, centiy), pmap)
- pmap = np.array(pmap, dtype=np.float)
+ occupancy_map = init_flood_fill((center_x, center_y), (ox, oy),
+ (x_w, y_w),
+ (min_x, min_y), xy_resolution)
+ flood_fill((center_x, center_y), occupancy_map)
+ occupancy_map = np.array(occupancy_map, dtype=float)
for (x, y) in zip(ox, oy):
- ix = int(round((x - minx) / xyreso))
- iy = int(round((y - miny) / xyreso))
- pmap[ix][iy] = 1.0 # occupied area 1.0
- pmap[ix+1][iy] = 1.0 # extend the occupied area
- pmap[ix][iy+1] = 1.0 # extend the occupied area
- pmap[ix+1][iy+1] = 1.0 # extend the occupied area
- return pmap, minx, maxx, miny, maxy, xyreso
+ ix = int(round((x - min_x) / xy_resolution))
+ iy = int(round((y - min_y) / xy_resolution))
+ occupancy_map[ix][iy] = 1.0 # occupied area 1.0
+ occupancy_map[ix + 1][iy] = 1.0 # extend the occupied area
+ occupancy_map[ix][iy + 1] = 1.0 # extend the occupied area
+ occupancy_map[ix + 1][iy + 1] = 1.0 # extend the occupied area
+ return occupancy_map, min_x, max_x, min_y, max_y, xy_resolution
def main():
@@ -191,18 +209,20 @@ def main():
Example usage
"""
print(__file__, "start")
- xyreso = 0.02 # x-y grid resolution
+ xy_resolution = 0.02 # x-y grid resolution
ang, dist = file_read("lidar01.csv")
ox = np.sin(ang) * dist
oy = np.cos(ang) * dist
- pmap, minx, maxx, miny, maxy, xyreso = generate_ray_casting_grid_map(ox, oy, xyreso, True)
- xyres = np.array(pmap).shape
- plt.figure(1, figsize=(10,4))
+ occupancy_map, min_x, max_x, min_y, max_y, xy_resolution = \
+ generate_ray_casting_grid_map(ox, oy, xy_resolution, True)
+ xy_res = np.array(occupancy_map).shape
+ plt.figure(1, figsize=(10, 4))
plt.subplot(122)
- plt.imshow(pmap, cmap="PiYG_r") # cmap = "binary" "PiYG_r" "PiYG_r" "bone" "bone_r" "RdYlGn_r"
+ plt.imshow(occupancy_map, cmap="PiYG_r")
+ # cmap = "binary" "PiYG_r" "PiYG_r" "bone" "bone_r" "RdYlGn_r"
plt.clim(-0.4, 1.4)
- plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor=True)
- plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor=True)
+ plt.gca().set_xticks(np.arange(-.5, xy_res[1], 1), minor=True)
+ plt.gca().set_yticks(np.arange(-.5, xy_res[0], 1), minor=True)
plt.grid(True, which="minor", color="w", linewidth=0.6, alpha=0.5)
plt.colorbar()
plt.subplot(121)
@@ -210,11 +230,11 @@ def main():
plt.axis("equal")
plt.plot(0.0, 0.0, "ob")
plt.gca().set_aspect("equal", "box")
- bottom, top = plt.ylim() # return the current ylim
- plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation
+ bottom, top = plt.ylim() # return the current y-lim
+ plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation
plt.grid(True)
plt.show()
-
+
if __name__ == '__main__':
- main()
+ main()
diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb b/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb
deleted file mode 100644
index 9e8a00f009..0000000000
--- a/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb
+++ /dev/null
@@ -1,318 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## LIDAR to 2D grid map example\n",
- "\n",
- "This simple tutorial shows how to read LIDAR (range) measurements from a file and convert it to occupancy grid.\n",
- "\n",
- "Occupancy grid maps (_Hans Moravec, A.E. Elfes: High resolution maps from wide angle sonar, Proc. IEEE Int. Conf. Robotics Autom. (1985)_) are a popular, probabilistic approach to represent the environment. The grid is basically discrete representation of the environment, which shows if a grid cell is occupied or not. Here the map is represented as a `numpy array`, and numbers close to 1 means the cell is occupied (_marked with red on the next image_), numbers close to 0 means they are free (_marked with green_). The grid has the ability to represent unknown (unobserved) areas, which are close to 0.5.\n",
- "\n",
- "\n",
- "\n",
- "\n",
- "In order to construct the grid map from the measurement we need to discretise the values. But, first let's need to `import` some necessary packages."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [],
- "source": [
- "import math\n",
- "import numpy as np\n",
- "import matplotlib.pyplot as plt\n",
- "from math import cos, sin, radians, pi"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "The measurement file contains the distances and the corresponding angles in a `csv` (comma separated values) format. Let's write the `file_read` method:"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [],
- "source": [
- "def file_read(f):\n",
- " \"\"\"\n",
- " Reading LIDAR laser beams (angles and corresponding distance data)\n",
- " \"\"\"\n",
- " measures = [line.split(\",\") for line in open(f)]\n",
- " angles = []\n",
- " distances = []\n",
- " for measure in measures:\n",
- " angles.append(float(measure[0]))\n",
- " distances.append(float(measure[1]))\n",
- " angles = np.array(angles)\n",
- " distances = np.array(distances)\n",
- " return angles, distances"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "From the distances and the angles it is easy to determine the `x` and `y` coordinates with `sin` and `cos`. \n",
- "In order to display it `matplotlib.pyplot` (`plt`) is used."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "ang, dist = file_read(\"lidar01.csv\")\n",
- "ox = np.sin(ang) * dist\n",
- "oy = np.cos(ang) * dist\n",
- "plt.figure(figsize=(6,10))\n",
- "plt.plot([oy, np.zeros(np.size(oy))], [ox, np.zeros(np.size(oy))], \"ro-\") # lines from 0,0 to the \n",
- "plt.axis(\"equal\")\n",
- "bottom, top = plt.ylim() # return the current ylim\n",
- "plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation\n",
- "plt.grid(True)\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "The `lidar_to_grid_map.py` contains handy functions which can used to convert a 2D range measurement to a grid map. For example the `bresenham` gives the a straight line between two points in a grid map. Let's see how this works."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 4,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "iVBORw0KGgoAAAANSUhEUgAAAS0AAAD8CAYAAAAi9vLQAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAEv5JREFUeJzt3X+s3XV9x/Hni0tLnY4BVkzXVumSboEsDramsLAsiDILGuqmLlS3wcJsloDDX9OyLYhkiZps4hZRcycNuDgKohl3pFuDFUJcHPQ6foy2QWqXybWNlV+KWyztva/9cb7F03PPPed7f/Se7+fe1yP55p7P9/u5n+/nkvLO5/P+fr6fI9tERJTipEF3ICJiOhK0IqIoCVoRUZQErYgoSoJWRBQlQSsiipKgFREnjKStkg5JemKK65L095L2SXpc0q/3azNBKyJOpNuADT2uXwqsrY7NwOf7NTiroCVpg6Qnqyi5ZTZtRcTCY/tB4LkeVTYCX3LLfwCnSVrRq82TZ9oZSUPALcAlwBiwS9KI7T1T/c5SneJlvHKmt4yIPn7K//KSD2s2bbzlja/0s8+N16r77ccP7wZ+2nZq2PbwNG63Eni6rTxWnTs41S/MOGgB64F9tvcDSNpGK2pOGbSW8UrO15tmccuI6OUh75x1G88+N87DO15Xq+7Qiqd+anvdLG7XLcD2fLdwNkGrW4Q8fxbtRUQDGJhgYr5uNwasbiuvAg70+oXZ5LRqRUhJmyWNSho9wuFZ3C4i5oMxRzxe65gDI8AfVU8RLwB+ZHvKqSHMbqRVK0JW89thgFN1RraUiCjAXI20JN0BXAQslzQGfAxYAmD7C8B24DJgH/B/wB/3a3M2QWsXsFbSGuD7wBXAu2fRXkQ0gDHjc7Rlle1Nfa4buGY6bc44aNk+KulaYAcwBGy1vXum7UVEc0z0zoUP1GxGWtjeTmt4FxELhIHxhRq0ImJhWrAjrRNhx4FHjyu/5RfPHVBPIhYnA0cavA1744JWRAyWcaaHEVEQw3hzY1aCVkQcr7UivrkaF7Q6c1jJcUXMNzHe9YWXZmhc0IqIwWol4hO0IqIQrXVaCVoRUZCJjLQiohQZaUVEUYwYb/DXRyRoRcQkmR5GRDGMeMlDg+7GlBK0IuI4rcWlmR7OWL/Fpt3qRMTsJBEfEcWwxbgz0oqIgkxkpBURpWgl4psbGprbsyl0y1/lpeqIuZNEfEQUZzzrtCKiFFkRHxHFmcjTw4goReuF6QStEyoLUCPmjhFH8hpPRJTCJotLI6IkyuLSiCiHyUgrIgqTRHxEFMMomwBGRDlaXyHW3NDQ3J5FxIDky1rnXV6qjpg5kxXxEVGYJo+0mhtOI2IgbDHhk2oddUjaIOlJSfskbely/fWSdkp6XNIDklb1ai9BKyKO00rED9U6+pE0BNwCXAqcA2ySdE5Htb8BvmT7DcBNwCd6tdk3aEnaKumQpCfazp0h6T5JT1U/T+/b+4goRGuP+DpHDeuBfbb3234J2AZs7KhzDrCz+nx/l+vHqZPTug34LPCltnNbgJ22P1kN97YAH63R1sD0e6k6ifmIllYivnZOa7mk0bbysO3htvJK4Om28hhwfkcbjwHvAP4O+F3g5yW92vaz3W7YN2jZflDSWR2nNwIXVZ9vBx6g4UErIuqbxor4Z2yv63G9W/RzR/nDwGclXQU8CHwfODpVgzN9evha2wcBbB+UdOZUFSVtBjYDLOPnZni7iJgvc7wifgxY3VZeBRw47n72AeD3ACS9CniH7R9N1eAJT8TbHra9zva6JZxyom8XEXNggpNqHTXsAtZKWiNpKXAFMNJeQdJySccaux7Y2qvBmY60fiBpRTXKWgEcmmE7A5ONAyO6s+HIxNyMZ2wflXQtsAMYArba3i3pJmDU9gitVNMnJJnW9PCaXm3ONGiNAFcCn6x+3jPDdiKiYVrTw7mbhNneDmzvOHdD2+e7gbvrttc3aEm6g1YkXC5pDPgYrWB1l6Srge8B76p7w4hoviaviK/z9HDTFJfeNMd9iYgGmOaSh3mXdw8josPcTg/nWoJWREySPeIjohitp4f5CrGIKES2W46I4mR6WIDsdhrRkqeHEVGcPD2MiGLY4miCVkSUJNPDQmXjwFiMktOKiOIkaEVEMbJOKyKKk3VaC0Q2DozFwIajc7QJ4ImQoBURk2R6GBHFSE4rIorjBK2IKEkS8RFRDDs5rYgoihjP08OIKElyWhFRjLx7uIBl48BYkNzKazVVglZETJKnhxFRDCcRHxGlyfRwEcnGgbEQ5OlhRBTDTtCKiMJkyUNEFCU5rYgohhETeXq4eGW30yhRgwdaNDecRsRgVIn4OkcdkjZIelLSPklbulx/naT7JT0i6XFJl/VqL0ErIiZzzaMPSUPALcClwDnAJknndFT7K+Au2+cBVwCf69Vm36AlaXUVBfdK2i3puur8GZLuk/RU9fP0/n9CRJRgDkda64F9tvfbfgnYBmzsvB1wavX5F4ADvRqsM9I6CnzI9tnABcA1VaTcAuy0vRbYWZUjonAGJiZU6wCWSxptOzZ3NLcSeLqtPFada3cj8AeSxoDtwPt69a9vIt72QeBg9flFSXurm24ELqqq3Q48AHy0X3sR0XAG6q/Tesb2uh7XuzXUObHcBNxm+28l/Sbwj5J+1fZEtwan9fRQ0lnAecBDwGurgIbtg5LOnE5bEdFcc7hOawxY3VZexeTp39XAhtZ9/S1Jy4DlwKFuDdZOxEt6FfBV4P22fzyN39t8bOh4hMN1fy0iBmmOEvHALmCtpDWSltJKtI901Pke8CYASWcDy4AfTtVgraAlaQmtgPVl21+rTv9A0orq+gqmiIq2h22vs71uCafUuV1EDFS9JHydRLzto8C1wA5gL62nhLsl3STp8qrah4D3SnoMuAO4yp56rNd3eihJwK3AXtufbrs0AlwJfLL6eU/fvyCy22mUYQ5Xl9reTivB3n7uhrbPe4AL67ZXJ6d1IfCHwH9JOvZ/11/QClZ3Sbqa1vDuXXVvGhENZvBEwS9M2/4m3Z8AQDUPjYiFpuCgFRGLUINfPkzQaoDsdhqNk6AVEcWY3uLSeZegFRGTZBPAiChLyU8PI2LxUUZaEVGM+q/oDESCVkR0UBLxEVGYjLQioihdd7JqhgStBso3+MRAZZ1WRJQmTw8joiwNDlr5CrGIKEpGWgXIxoEx3zI9jIhymLzGExGFyUgrIkqS6WHMuazlihMqQSsiipKgFRGlkDM9jIjS5OlhRJQkI62IKEuCVkQUIzmtiChOglZElETZBDBOtLxUHYtFglZETJbpYUQUI4n4iChOglYMQr+XqpPjiiklaEVEKUSznx5mj/iIOJ5/9tJ0v6MOSRskPSlpn6QtXa7fLOnR6viOpBd6tZeRVkRMNkfTQ0lDwC3AJcAYsEvSiO09L9/K/kBb/fcB5/Vqs+9IS9IySQ9LekzSbkkfr86vkfSQpKck3Slp6Qz/rohoGtc8+lsP7LO93/ZLwDZgY4/6m4A7ejVYZ6R1GLjY9k8kLQG+KelfgQ8CN9veJukLwNXA5+v8FTEY2e006prGkoflkkbbysO2h9vKK4Gn28pjwPld7ym9HlgDfKPXDfsGLdsGflIVl1SHgYuBd1fnbwduJEErYmGoH7Sesb2ux/VuG3NN1foVwN22x3vdsFYiXtKQpEeBQ8B9wHeBF2wfraqM0Yqo3X53s6RRSaNHOFzndhExSG49Paxz1DAGrG4rrwIOTFH3CvpMDaFm0LI9bvvc6obrgbO7VZvid4dtr7O9bgmn1LldRAza3OW0dgFrqxz4UlqBaaSzkqRfAU4HvtWvwWktebD9AvAAcAFwmqRj08te0TMiCjNXSx6q2di1wA5gL3CX7d2SbpJ0eVvVTcC2Kh3VU9+clqTXAEdsvyDpFcCbgU8B9wPvpPU04Ergnv5/QkQUYQ5XxNveDmzvOHdDR/nGuu3VeXq4Ari9Wm9xEq1Iea+kPcA2SX8NPALcWvemEdFg9ad+A1Hn6eHjdFnsZXs/rfxWRCwgIrs8RERhErSikbLbaUwpQSsiipKgFRHFyM6lEVGcBK0oRXY7DWj2JoAJWhExSaaHEVGO0heXRsQilKAVpcrGgYtPVsRHRHE00dyolaAVEcdLTisiSpPpYUSUJUErIkqSkVZElCVBKyKK4bzGExEFyTqtWFCyceAi0f9LcQYmQSsiJslIKyLKkcWlEVGaJOJjQcvGgQtPglZElMMkER8RZUkiPiLKkqAVEaXI4tJYdLLbaeHsbAIYEYVpbsxK0IqIyTI9jIhyGMj0MCKK0tyYxUmD7kBENI9c76jVlrRB0pOS9knaMkWd35e0R9JuSf/Uq72MtCJikrl6eihpCLgFuAQYA3ZJGrG9p63OWuB64ELbz0s6s1ebtUdakoYkPSLp3qq8RtJDkp6SdKekpTP5oyKiYTyNo7/1wD7b+22/BGwDNnbUeS9wi+3nAWwf6tXgdEZa1wF7gVOr8qeAm21vk/QF4Grg89NoLxaJbBxYltbi0tojreWSRtvKw7aH28orgafbymPA+R1t/DKApH8HhoAbbf/bVDesNdKStAp4K/DFqizgYuDuqsrtwNvrtBURBZioecAztte1HcMdLalL650R8WRgLXARsAn4oqTTpupa3enhZ4CPvNxNeDXwgu2jVXmMVkSdRNJmSaOSRo9wuObtImKQZNc6ahgDVreVVwEHutS5x/YR2/8NPEkriHXVN2hJehtwyPa32093qdr1L7A9fCwKL+GUfreLiEGb25zWLmBtlQNfClwBjHTU+WfgjQCSltOaLu6fqsE6Oa0LgcslXQYso5XT+gxwmqSTq9FWt+gZEUWau3cPbR+VdC2wg1a+aqvt3ZJuAkZtj1TXfkfSHmAc+HPbz07VZt+gZft6Wo8jkXQR8GHb75H0FeCdtJ4GXAncM6u/LhaVJN4bbg43AbS9Hdjece6Gts8GPlgdfc1mcelHgQ9K2kcrx3XrLNqKiKaovqy1zjEI01pcavsB4IHq835aazAiYqHJdssRUZTmxqwErYiYTBPN/TqeBK2IOJ752YrMBkrQiojjiNoLRwciQSsiJkvQioiiJGhFRDGS04qI0uTpYUQUxJkeRkRBTIJWRBSmubPDBK2ImCzrtCKiLAlaEVEMG8abOz9M0IqIyTLSioiiJGhFRDEMzNEe8SdCglZEdDA4Oa2IKIVJIj4iCpOcVkQUJUErIsqRF6YjoiQGsjVNRBQlI62IKEde44mIkhicdVoRUZSsiI+IoiSnFRHFsPP0MCIKk5FWRJTDeHx80J2YUoJWRBwvW9NERHEavOThpEF3ICKaxYAnXOuoQ9IGSU9K2idpS5frV0n6oaRHq+NPerWXkVZEHM9ztwmgpCHgFuASYAzYJWnE9p6OqnfavrZOmwlaETHJHCbi1wP7bO8HkLQN2Ah0Bq3a5jVovcjzz3zdd/8PsBx4Zj7vPQsl9RXK6m9JfYUy+vv62TbwIs/v+LrvXl6z+jJJo23lYdvDbeWVwNNt5THg/C7tvEPSbwPfAT5g++kudYB5Dlq2XwMgadT2uvm890yV1Fcoq78l9RXK6+9M2d4wh82p2y06yv8C3GH7sKQ/BW4HLp6qwSTiI+JEGgNWt5VXAQfaK9h+1vbhqvgPwG/0ajBBKyJOpF3AWklrJC0FrgBG2itIWtFWvBzY26vBQSXih/tXaYyS+gpl9bekvkJ5/R0420clXQvsAIaArbZ3S7oJGLU9AvyZpMuBo8BzwFW92pQb/I5RRESnTA8joigJWhFRlHkNWv2W8w+apK2SDkl6ou3cGZLuk/RU9fP0QfbxGEmrJd0vaa+k3ZKuq843tb/LJD0s6bGqvx+vzq+R9FDV3zurZG0jSBqS9Iike6tyY/u6mMxb0Gpbzn8pcA6wSdI583X/mm4DOteobAF22l4L7KzKTXAU+JDts4ELgGuq/55N7e9h4GLbvwacC2yQdAHwKeDmqr/PA1cPsI+druP4J1lN7uuiMZ8jrZeX89t+CTi2nL8xbD9I6+lFu420FrtR/Xz7vHZqCrYP2v7P6vOLtP7nWklz+2vbP6mKS6rDtBYR3l2db0x/Ja0C3gp8sSqLhvZ1sZnPoNVtOf/Kebz/TL3W9kFoBQrgzAH3ZxJJZwHnAQ/R4P5W061HgUPAfcB3gRdsH62qNOnfxGeAjwDH3hx+Nc3t66Iyn0GrznL+mCZJrwK+Crzf9o8H3Z9ebI/bPpfWquj1wNndqs1vryaT9DbgkO1vt5/uUnXgfV2M5nNxad/l/A31A0krbB+sVu4eGnSHjpG0hFbA+rLtr1WnG9vfY2y/IOkBWrm40ySdXI1gmvJv4kLgckmXAcuAU2mNvJrY10VnPkdafZfzN9QIcGX1+UrgngH25WVVjuVWYK/tT7ddamp/XyPptOrzK4A308rD3Q+8s6rWiP7avt72Kttn0fp3+g3b76GBfV2UbM/bAVxGa+uJ7wJ/OZ/3rtm/O4CDwBFaI8OraeUydgJPVT/PGHQ/q77+Fq3pyePAo9VxWYP7+wbgkaq/TwA3VOd/CXgY2Ad8BThl0H3t6PdFwL0l9HWxHHmNJyKKkhXxEVGUBK2IKEqCVkQUJUErIoqSoBURRUnQioiiJGhFRFH+H4+m+nkliYroAAAAAElFTkSuQmCC\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "import lidar_to_grid_map as lg\n",
- "map1 = np.ones((50, 50)) * 0.5\n",
- "line = lg.bresenham((2, 2), (40, 30))\n",
- "for l in line:\n",
- " map1[l[0]][l[1]] = 1\n",
- "plt.imshow(map1)\n",
- "plt.colorbar()\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "line = lg.bresenham((2, 30), (40, 30))\n",
- "for l in line:\n",
- " map1[l[0]][l[1]] = 1\n",
- "line = lg.bresenham((2, 30), (2, 2))\n",
- "for l in line:\n",
- " map1[l[0]][l[1]] = 1\n",
- "plt.imshow(map1)\n",
- "plt.colorbar()\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "To fill empty areas, a queue-based algorithm can be used that can be used on an initialized occupancy map. The center point is given: the algorithm checks for neighbour elements in each iteration, and stops expansion on obstacles and free boundaries."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 6,
- "metadata": {},
- "outputs": [],
- "source": [
- "from collections import deque\n",
- "def flood_fill(cpoint, pmap):\n",
- " \"\"\"\n",
- " cpoint: starting point (x,y) of fill\n",
- " pmap: occupancy map generated from Bresenham ray-tracing\n",
- " \"\"\"\n",
- " # Fill empty areas with queue method\n",
- " sx, sy = pmap.shape\n",
- " fringe = deque()\n",
- " fringe.appendleft(cpoint)\n",
- " while fringe:\n",
- " n = fringe.pop()\n",
- " nx, ny = n\n",
- " # West\n",
- " if nx > 0:\n",
- " if pmap[nx - 1, ny] == 0.5:\n",
- " pmap[nx - 1, ny] = 0.0\n",
- " fringe.appendleft((nx - 1, ny))\n",
- " # East\n",
- " if nx < sx - 1:\n",
- " if pmap[nx + 1, ny] == 0.5:\n",
- " pmap[nx + 1, ny] = 0.0\n",
- " fringe.appendleft((nx + 1, ny))\n",
- " # North\n",
- " if ny > 0:\n",
- " if pmap[nx, ny - 1] == 0.5:\n",
- " pmap[nx, ny - 1] = 0.0\n",
- " fringe.appendleft((nx, ny - 1))\n",
- " # South\n",
- " if ny < sy - 1:\n",
- " if pmap[nx, ny + 1] == 0.5:\n",
- " pmap[nx, ny + 1] = 0.0\n",
- " fringe.appendleft((nx, ny + 1))"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "This algotihm will fill the area bounded by the yellow lines starting from a center point (e.g. (10, 20)) with zeros:"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 7,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "flood_fill((10, 20), map1)\n",
- "map_float = np.array(map1)/10.0\n",
- "plt.imshow(map1)\n",
- "plt.colorbar()\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Let's use this flood fill on real data:"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 8,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "The grid map is 150 x 100 .\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "xyreso = 0.02 # x-y grid resolution\n",
- "yawreso = math.radians(3.1) # yaw angle resolution [rad]\n",
- "ang, dist = file_read(\"lidar01.csv\")\n",
- "ox = np.sin(ang) * dist\n",
- "oy = np.cos(ang) * dist\n",
- "pmap, minx, maxx, miny, maxy, xyreso = lg.generate_ray_casting_grid_map(ox, oy, xyreso, False)\n",
- "xyres = np.array(pmap).shape\n",
- "plt.figure(figsize=(20,8))\n",
- "plt.subplot(122)\n",
- "plt.imshow(pmap, cmap = \"PiYG_r\") \n",
- "plt.clim(-0.4, 1.4)\n",
- "plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor = True)\n",
- "plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor = True)\n",
- "plt.grid(True, which=\"minor\", color=\"w\", linewidth = .6, alpha = 0.5)\n",
- "plt.colorbar()\n",
- "plt.show()"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.7.3"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/Mapping/ndt_map/ndt_map.py b/Mapping/ndt_map/ndt_map.py
new file mode 100644
index 0000000000..f4f3299662
--- /dev/null
+++ b/Mapping/ndt_map/ndt_map.py
@@ -0,0 +1,135 @@
+"""
+Normal Distribution Transform (NDTGrid) mapping sample
+"""
+import matplotlib.pyplot as plt
+import numpy as np
+from collections import defaultdict
+
+from Mapping.grid_map_lib.grid_map_lib import GridMap
+from utils.plot import plot_covariance_ellipse
+
+
+class NDTMap:
+ """
+ Normal Distribution Transform (NDT) map class
+
+ :param ox: obstacle x position list
+ :param oy: obstacle y position list
+ :param resolution: grid resolution [m]
+ """
+
+ class NDTGrid:
+ """
+ NDT grid
+ """
+
+ def __init__(self):
+ #: Number of points in the NDTGrid grid
+ self.n_points = 0
+ #: Mean x position of points in the NDTGrid cell
+ self.mean_x = None
+ #: Mean y position of points in the NDTGrid cell
+ self.mean_y = None
+ #: Center x position of the NDT grid
+ self.center_grid_x = None
+ #: Center y position of the NDT grid
+ self.center_grid_y = None
+ #: Covariance matrix of the NDT grid
+ self.covariance = None
+ #: Eigen vectors of the NDT grid
+ self.eig_vec = None
+ #: Eigen values of the NDT grid
+ self.eig_values = None
+
+ def __init__(self, ox, oy, resolution):
+ #: Minimum number of points in the NDT grid
+ self.min_n_points = 3
+ #: Resolution of the NDT grid [m]
+ self.resolution = resolution
+ width = int((max(ox) - min(ox))/resolution) + 3 # rounding up + right and left margin
+ height = int((max(oy) - min(oy))/resolution) + 3
+ center_x = np.mean(ox)
+ center_y = np.mean(oy)
+ self.ox = ox
+ self.oy = oy
+ #: NDT grid index map
+ self.grid_index_map = self._create_grid_index_map(ox, oy)
+
+ #: NDT grid map. Each grid contains NDTGrid object
+ self._construct_grid_map(center_x, center_y, height, ox, oy, resolution, width)
+
+ def _construct_grid_map(self, center_x, center_y, height, ox, oy, resolution, width):
+ self.grid_map = GridMap(width, height, resolution, center_x, center_y, self.NDTGrid())
+ for grid_index, inds in self.grid_index_map.items():
+ ndt = self.NDTGrid()
+ ndt.n_points = len(inds)
+ if ndt.n_points >= self.min_n_points:
+ ndt.mean_x = np.mean(ox[inds])
+ ndt.mean_y = np.mean(oy[inds])
+ ndt.center_grid_x, ndt.center_grid_y = \
+ self.grid_map.calc_grid_central_xy_position_from_grid_index(grid_index)
+ ndt.covariance = np.cov(ox[inds], oy[inds])
+ ndt.eig_values, ndt.eig_vec = np.linalg.eig(ndt.covariance)
+ self.grid_map.data[grid_index] = ndt
+
+ def _create_grid_index_map(self, ox, oy):
+ grid_index_map = defaultdict(list)
+ for i in range(len(ox)):
+ grid_index = self.grid_map.calc_grid_index_from_xy_pos(ox[i], oy[i])
+ grid_index_map[grid_index].append(i)
+ return grid_index_map
+
+
+def create_dummy_observation_data():
+ ox = []
+ oy = []
+ # left corridor
+ for y in range(-50, 50):
+ ox.append(-20.0)
+ oy.append(y)
+ # right corridor 1
+ for y in range(-50, 0):
+ ox.append(20.0)
+ oy.append(y)
+ # right corridor 2
+ for x in range(20, 50):
+ ox.append(x)
+ oy.append(0)
+ # right corridor 3
+ for x in range(20, 50):
+ ox.append(x)
+ oy.append(x/2.0+10)
+ # right corridor 4
+ for y in range(20, 50):
+ ox.append(20)
+ oy.append(y)
+ ox = np.array(ox)
+ oy = np.array(oy)
+ # Adding random noize
+ ox += np.random.rand(len(ox)) * 1.0
+ oy += np.random.rand(len(ox)) * 1.0
+ return ox, oy
+
+
+def main():
+ print(__file__ + " start!!")
+
+ ox, oy = create_dummy_observation_data()
+ grid_resolution = 10.0
+ ndt_map = NDTMap(ox, oy, grid_resolution)
+
+ # plot raw observation
+ plt.plot(ox, oy, ".r")
+
+ # plot grid clustering
+ [plt.plot(ox[inds], oy[inds], "x") for inds in ndt_map.grid_index_map.values()]
+
+ # plot ndt grid map
+ [plot_covariance_ellipse(ndt.mean_x, ndt.mean_y, ndt.covariance, color="-k") for ndt in ndt_map.grid_map.data if ndt.n_points > 0]
+
+ plt.axis("equal")
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/Mapping/normal_vector_estimation/normal_vector_estimation.py b/Mapping/normal_vector_estimation/normal_vector_estimation.py
new file mode 100644
index 0000000000..996ba3ffee
--- /dev/null
+++ b/Mapping/normal_vector_estimation/normal_vector_estimation.py
@@ -0,0 +1,177 @@
+import numpy as np
+from matplotlib import pyplot as plt
+
+from utils.plot import plot_3d_vector_arrow, plot_triangle, set_equal_3d_axis
+
+show_animation = True
+
+
+def calc_normal_vector(p1, p2, p3):
+ """Calculate normal vector of triangle
+
+ Parameters
+ ----------
+ p1 : np.array
+ 3D point
+ p2 : np.array
+ 3D point
+ p3 : np.array
+ 3D point
+
+ Returns
+ -------
+ normal_vector : np.array
+ normal vector (3,)
+
+ """
+ # calculate two vectors of triangle
+ v1 = p2 - p1
+ v2 = p3 - p1
+
+ # calculate normal vector
+ normal_vector = np.cross(v1, v2)
+
+ # normalize vector
+ normal_vector = normal_vector / np.linalg.norm(normal_vector)
+
+ return normal_vector
+
+
+def sample_3d_points_from_a_plane(num_samples, normal):
+ points_2d = np.random.normal(size=(num_samples, 2)) # 2D points on a plane
+ d = 0
+ for i in range(len(points_2d)):
+ point_3d = np.append(points_2d[i], 0)
+ d += normal @ point_3d
+ d /= len(points_2d)
+
+ points_3d = np.zeros((len(points_2d), 3))
+ for i in range(len(points_2d)):
+ point_2d = np.append(points_2d[i], 0)
+ projection_length = (d - normal @ point_2d) / np.linalg.norm(normal)
+ points_3d[i] = point_2d + projection_length * normal
+
+ return points_3d
+
+
+def distance_to_plane(point, normal, origin):
+ dot_product = np.dot(normal, point) - np.dot(normal, origin)
+ if np.isclose(dot_product, 0):
+ return 0.0
+ else:
+ distance = abs(dot_product) / np.linalg.norm(normal)
+ return distance
+
+
+def ransac_normal_vector_estimation(points_3d, inlier_radio_th=0.7,
+ inlier_dist=0.1, p=0.99):
+ """
+ RANSAC based normal vector estimation
+
+ Parameters
+ ----------
+ points_3d : np.array
+ 3D points (N, 3)
+ inlier_radio_th : float
+ Inlier ratio threshold. If inlier ratio is larger than this value,
+ the iteration is stopped. Default is 0.7.
+ inlier_dist : float
+ Inlier distance threshold. If distance between points and estimated
+ plane is smaller than this value, the point is inlier. Default is 0.1.
+ p : float
+ Probability that at least one of the sets of random samples does not
+ include an outlier. If this probability is near 1, the iteration
+ number is large. Default is 0.99.
+
+ Returns
+ -------
+ center_vector : np.array
+ Center of estimated plane. (3,)
+ normal_vector : np.array
+ Normal vector of estimated plane. (3,)
+
+ """
+ center = np.mean(points_3d, axis=0)
+
+ max_iter = int(np.floor(np.log(1.0-p)/np.log(1.0-(1.0-inlier_radio_th)**3)))
+
+ for ite in range(max_iter):
+ # Random sampling
+ sampled_ids = np.random.choice(points_3d.shape[0], size=3,
+ replace=False)
+ sampled_points = points_3d[sampled_ids, :]
+ p1 = sampled_points[0, :]
+ p2 = sampled_points[1, :]
+ p3 = sampled_points[2, :]
+ normal_vector = calc_normal_vector(p1, p2, p3)
+
+ # calc inlier ratio
+ n_inliner = 0
+ for i in range(points_3d.shape[0]):
+ p = points_3d[i, :]
+ if distance_to_plane(p, normal_vector, center) <= inlier_dist:
+ n_inliner += 1
+ inlier_ratio = n_inliner / points_3d.shape[0]
+ print(f"Iter:{ite}, {inlier_ratio=}")
+ if inlier_ratio > inlier_radio_th:
+ return center, normal_vector
+
+ return center, None
+
+
+def main1():
+ p1 = np.array([0.0, 0.0, 1.0])
+ p2 = np.array([1.0, 1.0, 0.0])
+ p3 = np.array([0.0, 1.0, 0.0])
+
+ center = np.mean([p1, p2, p3], axis=0)
+ normal_vector = calc_normal_vector(p1, p2, p3)
+ print(f"{center=}")
+ print(f"{normal_vector=}")
+
+ if show_animation:
+ fig = plt.figure()
+ ax = fig.add_subplot(projection='3d')
+ set_equal_3d_axis(ax, [0.0, 2.5], [0.0, 2.5], [0.0, 3.0])
+ plot_triangle(p1, p2, p3, ax)
+ ax.plot(center[0], center[1], center[2], "ro")
+ plot_3d_vector_arrow(ax, center, center + normal_vector)
+ plt.show()
+
+
+def main2(rng=None):
+ true_normal = np.array([0, 1, 1])
+ true_normal = true_normal / np.linalg.norm(true_normal)
+ num_samples = 100
+ noise_scale = 0.1
+
+ points_3d = sample_3d_points_from_a_plane(num_samples, true_normal)
+ # add random noise
+ points_3d += np.random.normal(size=points_3d.shape, scale=noise_scale)
+
+ print(f"{points_3d.shape=}")
+
+ center, estimated_normal = ransac_normal_vector_estimation(
+ points_3d, inlier_dist=noise_scale)
+
+ if estimated_normal is None:
+ print("Failed to estimate normal vector")
+ return
+
+ print(f"{true_normal=}")
+ print(f"{estimated_normal=}")
+
+ if show_animation:
+ fig = plt.figure()
+ ax = fig.add_subplot(projection='3d')
+ ax.plot(points_3d[:, 0], points_3d[:, 1], points_3d[:, 2], ".r")
+ plot_3d_vector_arrow(ax, center, center + true_normal)
+ plot_3d_vector_arrow(ax, center, center + estimated_normal)
+ set_equal_3d_axis(ax, [-3.0, 3.0], [-3.0, 3.0], [-3.0, 3.0])
+ plt.title("RANSAC based Normal vector estimation")
+ plt.show()
+
+
+if __name__ == '__main__':
+ # main1()
+ main2()
diff --git a/Mapping/point_cloud_sampling/point_cloud_sampling.py b/Mapping/point_cloud_sampling/point_cloud_sampling.py
new file mode 100644
index 0000000000..df7cde41c0
--- /dev/null
+++ b/Mapping/point_cloud_sampling/point_cloud_sampling.py
@@ -0,0 +1,168 @@
+"""
+Point cloud sampling example codes. This code supports
+- Voxel point sampling
+- Farthest point sampling
+- Poisson disk sampling
+
+"""
+import matplotlib.pyplot as plt
+import numpy as np
+import numpy.typing as npt
+from collections import defaultdict
+
+do_plot = True
+
+
+def voxel_point_sampling(original_points: npt.NDArray, voxel_size: float):
+ """
+ Voxel Point Sampling function.
+ This function sample N-dimensional points with voxel grid.
+ Points in a same voxel grid will be merged by mean operation for sampling.
+
+ Parameters
+ ----------
+ original_points : (M, N) N-dimensional points for sampling.
+ The number of points is M.
+ voxel_size : voxel grid size
+
+ Returns
+ -------
+ sampled points (M', N)
+ """
+ voxel_dict = defaultdict(list)
+ for i in range(original_points.shape[0]):
+ xyz = original_points[i, :]
+ xyz_index = tuple(xyz // voxel_size)
+ voxel_dict[xyz_index].append(xyz)
+ points = np.vstack([np.mean(v, axis=0) for v in voxel_dict.values()])
+ return points
+
+
+def farthest_point_sampling(orig_points: npt.NDArray,
+ n_points: int, seed: int):
+ """
+ Farthest point sampling function
+ This function sample N-dimensional points with the farthest point policy.
+
+ Parameters
+ ----------
+ orig_points : (M, N) N-dimensional points for sampling.
+ The number of points is M.
+ n_points : number of points for sampling
+ seed : random seed number
+
+ Returns
+ -------
+ sampled points (n_points, N)
+
+ """
+ rng = np.random.default_rng(seed)
+ n_orig_points = orig_points.shape[0]
+ first_point_id = rng.choice(range(n_orig_points))
+ min_distances = np.ones(n_orig_points) * float("inf")
+ selected_ids = [first_point_id]
+ while len(selected_ids) < n_points:
+ base_point = orig_points[selected_ids[-1], :]
+ distances = np.linalg.norm(orig_points[np.newaxis, :] - base_point,
+ axis=2).flatten()
+ min_distances = np.minimum(min_distances, distances)
+ distances_rank = np.argsort(-min_distances) # Farthest order
+ for i in distances_rank: # From the farthest point
+ if i not in selected_ids: # if not selected yes, select it
+ selected_ids.append(i)
+ break
+ return orig_points[selected_ids, :]
+
+
+def poisson_disk_sampling(orig_points: npt.NDArray, n_points: int,
+ min_distance: float, seed: int, MAX_ITER=1000):
+ """
+ Poisson disk sampling function
+ This function sample N-dimensional points randomly until the number of
+ points keeping minimum distance between selected points.
+
+ Parameters
+ ----------
+ orig_points : (M, N) N-dimensional points for sampling.
+ The number of points is M.
+ n_points : number of points for sampling
+ min_distance : minimum distance between selected points.
+ seed : random seed number
+ MAX_ITER : Maximum number of iteration. Default is 1000.
+
+ Returns
+ -------
+ sampled points (n_points or less, N)
+ """
+ rng = np.random.default_rng(seed)
+ selected_id = rng.choice(range(orig_points.shape[0]))
+ selected_ids = [selected_id]
+ loop = 0
+ while len(selected_ids) < n_points and loop <= MAX_ITER:
+ selected_id = rng.choice(range(orig_points.shape[0]))
+ base_point = orig_points[selected_id, :]
+ distances = np.linalg.norm(
+ orig_points[np.newaxis, selected_ids] - base_point,
+ axis=2).flatten()
+ if min(distances) >= min_distance:
+ selected_ids.append(selected_id)
+ loop += 1
+ if len(selected_ids) != n_points:
+ print("Could not find the specified number of points...")
+
+ return orig_points[selected_ids, :]
+
+
+def plot_sampled_points(original_points, sampled_points, method_name):
+ fig = plt.figure()
+ ax = fig.add_subplot(projection='3d')
+ ax.scatter(original_points[:, 0], original_points[:, 1],
+ original_points[:, 2], marker=".", label="Original points")
+ ax.scatter(sampled_points[:, 0], sampled_points[:, 1],
+ sampled_points[:, 2], marker="o",
+ label="Filtered points")
+ plt.legend()
+ plt.title(method_name)
+ plt.axis("equal")
+
+
+def main():
+ n_points = 1000
+ seed = 1234
+ rng = np.random.default_rng(seed)
+
+ x = rng.normal(0.0, 10.0, n_points)
+ y = rng.normal(0.0, 1.0, n_points)
+ z = rng.normal(0.0, 10.0, n_points)
+ original_points = np.vstack((x, y, z)).T
+ print(f"{original_points.shape=}")
+ print("Voxel point sampling")
+ voxel_size = 20.0
+ voxel_sampling_points = voxel_point_sampling(original_points, voxel_size)
+ print(f"{voxel_sampling_points.shape=}")
+
+ print("Farthest point sampling")
+ n_points = 20
+ farthest_sampling_points = farthest_point_sampling(original_points,
+ n_points, seed)
+ print(f"{farthest_sampling_points.shape=}")
+
+ print("Poisson disk sampling")
+ n_points = 20
+ min_distance = 10.0
+ poisson_disk_points = poisson_disk_sampling(original_points, n_points,
+ min_distance, seed)
+ print(f"{poisson_disk_points.shape=}")
+
+ if do_plot:
+ plot_sampled_points(original_points, voxel_sampling_points,
+ "Voxel point sampling")
+ plot_sampled_points(original_points, farthest_sampling_points,
+ "Farthest point sampling")
+ plot_sampled_points(original_points, poisson_disk_points,
+ "poisson disk sampling")
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/Mapping/raycasting_grid_map/raycasting_grid_map.py b/Mapping/ray_casting_grid_map/ray_casting_grid_map.py
similarity index 89%
rename from Mapping/raycasting_grid_map/raycasting_grid_map.py
rename to Mapping/ray_casting_grid_map/ray_casting_grid_map.py
index 997687423e..c7e73f0630 100644
--- a/Mapping/raycasting_grid_map/raycasting_grid_map.py
+++ b/Mapping/ray_casting_grid_map/ray_casting_grid_map.py
@@ -48,7 +48,7 @@ def atan_zero_to_twopi(y, x):
return angle
-def precasting(minx, miny, xw, yw, xyreso, yawreso):
+def pre_casting(minx, miny, xw, yw, xyreso, yawreso):
precast = [[] for i in range(int(round((math.pi * 2.0) / yawreso)) + 1)]
@@ -57,7 +57,7 @@ def precasting(minx, miny, xw, yw, xyreso, yawreso):
px = ix * xyreso + minx
py = iy * xyreso + miny
- d = math.sqrt(px**2 + py**2)
+ d = math.hypot(px, py)
angle = atan_zero_to_twopi(py, px)
angleid = int(math.floor(angle / yawreso))
@@ -81,11 +81,11 @@ def generate_ray_casting_grid_map(ox, oy, xyreso, yawreso):
pmap = [[0.0 for i in range(yw)] for i in range(xw)]
- precast = precasting(minx, miny, xw, yw, xyreso, yawreso)
+ precast = pre_casting(minx, miny, xw, yw, xyreso, yawreso)
for (x, y) in zip(ox, oy):
- d = math.sqrt(x**2 + y**2)
+ d = math.hypot(x, y)
angle = atan_zero_to_twopi(y, x)
angleid = int(math.floor(angle / yawreso))
@@ -124,6 +124,9 @@ def main():
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
draw_heatmap(pmap, minx, maxx, miny, maxy, xyreso)
plt.plot(ox, oy, "xr")
plt.plot(0.0, 0.0, "ob")
diff --git a/Mapping/rectangle_fitting/__init_.py b/Mapping/rectangle_fitting/__init_.py
new file mode 100644
index 0000000000..2194d4c303
--- /dev/null
+++ b/Mapping/rectangle_fitting/__init_.py
@@ -0,0 +1,3 @@
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent))
diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py
index e40fc2e4c7..7902619666 100644
--- a/Mapping/rectangle_fitting/rectangle_fitting.py
+++ b/Mapping/rectangle_fitting/rectangle_fitting.py
@@ -4,22 +4,37 @@
author: Atsushi Sakai (@Atsushi_twi)
-Ref:
-- [Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University](https://www.ri.cmu.edu/publications/efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/)
+Reference:
+- Efficient L-Shape Fitting for Vehicle Detection Using Laser Scanners -
+The Robotics Institute Carnegie Mellon University
+https://www.ri.cmu.edu/publications/
+efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
import matplotlib.pyplot as plt
import numpy as np
import itertools
from enum import Enum
-from simulator import VehicleSimulator, LidarSimulator
+from utils.angle import rot_mat_2d
+
+from Mapping.rectangle_fitting.simulator \
+ import VehicleSimulator, LidarSimulator
show_animation = True
-class LShapeFitting():
+class LShapeFitting:
+ """
+ LShapeFitting class. You can use this class by initializing the class and
+ changing the parameters, and then calling the fitting method.
+
+ """
class Criteria(Enum):
AREA = 1
@@ -27,100 +42,101 @@ class Criteria(Enum):
VARIANCE = 3
def __init__(self):
- # Parameters
+ """
+ Default parameter settings
+ """
+ #: Fitting criteria parameter
self.criteria = self.Criteria.VARIANCE
- self.min_dist_of_closeness_crit = 0.01 # [m]
- self.dtheta_deg_for_serarch = 1.0 # [deg]
- self.R0 = 3.0 # [m] range segmentation param
- self.Rd = 0.001 # [m] range segmentation param
+ #: Minimum distance for closeness criteria parameter [m]
+ self.min_dist_of_closeness_criteria = 0.01
+ #: Angle difference parameter [deg]
+ self.d_theta_deg_for_search = 1.0
+ #: Range segmentation parameter [m]
+ self.R0 = 3.0
+ #: Range segmentation parameter [m]
+ self.Rd = 0.001
def fitting(self, ox, oy):
+ """
+ Fitting L-shape model to object points
+
+ Parameters
+ ----------
+ ox : x positions of range points from an object
+ oy : y positions of range points from an object
+ Returns
+ -------
+ rects: Fitting rectangles
+ id_sets: id sets of each cluster
+
+ """
# step1: Adaptive Range Segmentation
- idsets = self._adoptive_range_segmentation(ox, oy)
+ id_sets = self._adoptive_range_segmentation(ox, oy)
# step2 Rectangle search
rects = []
- for ids in idsets: # for each cluster
+ for ids in id_sets: # for each cluster
cx = [ox[i] for i in range(len(ox)) if i in ids]
cy = [oy[i] for i in range(len(oy)) if i in ids]
rects.append(self._rectangle_search(cx, cy))
- return rects, idsets
-
- def _calc_area_criterion(self, c1, c2):
- c1_max = max(c1)
- c2_max = max(c2)
- c1_min = min(c1)
- c2_min = min(c2)
+ return rects, id_sets
+ @staticmethod
+ def _calc_area_criterion(c1, c2):
+ c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2)
alpha = -(c1_max - c1_min) * (c2_max - c2_min)
-
return alpha
def _calc_closeness_criterion(self, c1, c2):
- c1_max = max(c1)
- c2_max = max(c2)
- c1_min = min(c1)
- c2_min = min(c2)
-
- D1 = [min([np.linalg.norm(c1_max - ic1),
- np.linalg.norm(ic1 - c1_min)]) for ic1 in c1]
- D2 = [min([np.linalg.norm(c2_max - ic2),
- np.linalg.norm(ic2 - c2_min)]) for ic2 in c2]
+ c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2)
- beta = 0
- for i, _ in enumerate(D1):
- d = max(min([D1[i], D2[i]]), self.min_dist_of_closeness_crit)
- beta += (1.0 / d)
+ # Vectorization
+ d1 = np.minimum(c1_max - c1, c1 - c1_min)
+ d2 = np.minimum(c2_max - c2, c2 - c2_min)
+ d = np.maximum(np.minimum(d1, d2), self.min_dist_of_closeness_criteria)
+ beta = (1.0 / d).sum()
return beta
- def _calc_variance_criterion(self, c1, c2):
+ @staticmethod
+ def _calc_variance_criterion(c1, c2):
+ c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2)
+
+ # Vectorization
+ d1 = np.minimum(c1_max - c1, c1 - c1_min)
+ d2 = np.minimum(c2_max - c2, c2 - c2_min)
+ e1 = d1[d1 < d2]
+ e2 = d2[d1 >= d2]
+ v1 = - np.var(e1) if len(e1) > 0 else 0.
+ v2 = - np.var(e2) if len(e2) > 0 else 0.
+ gamma = v1 + v2
+
+ return gamma
+
+ @staticmethod
+ def _find_min_max(c1, c2):
c1_max = max(c1)
c2_max = max(c2)
c1_min = min(c1)
c2_min = min(c2)
-
- D1 = [min([np.linalg.norm(c1_max - ic1),
- np.linalg.norm(ic1 - c1_min)]) for ic1 in c1]
- D2 = [min([np.linalg.norm(c2_max - ic2),
- np.linalg.norm(ic2 - c2_min)]) for ic2 in c2]
-
- E1, E2 = [], []
- for (d1, d2) in zip(D1, D2):
- if d1 < d2:
- E1.append(d1)
- else:
- E2.append(d2)
-
- V1 = 0.0
- if E1:
- V1 = - np.var(E1)
-
- V2 = 0.0
- if E2:
- V2 = - np.var(E2)
-
- gamma = V1 + V2
-
- return gamma
+ return c1_max, c1_min, c2_max, c2_min
def _rectangle_search(self, x, y):
- X = np.array([x, y]).T
-
- dtheta = np.deg2rad(self.dtheta_deg_for_serarch)
- minp = (-float('inf'), None)
- for theta in np.arange(0.0, np.pi / 2.0 - dtheta, dtheta):
+ xy = np.array([x, y]).T
- e1 = np.array([np.cos(theta), np.sin(theta)])
- e2 = np.array([-np.sin(theta), np.cos(theta)])
+ d_theta = np.deg2rad(self.d_theta_deg_for_search)
+ min_cost = (-float('inf'), None)
+ for theta in np.arange(0.0, np.pi / 2.0 - d_theta, d_theta):
- c1 = X @ e1.T
- c2 = X @ e2.T
+ c = xy @ rot_mat_2d(theta)
+ c1 = c[:, 0]
+ c2 = c[:, 1]
# Select criteria
+ cost = 0.0
if self.criteria == self.Criteria.AREA:
cost = self._calc_area_criterion(c1, c2)
elif self.criteria == self.Criteria.CLOSENESS:
@@ -128,15 +144,15 @@ def _rectangle_search(self, x, y):
elif self.criteria == self.Criteria.VARIANCE:
cost = self._calc_variance_criterion(c1, c2)
- if minp[0] < cost:
- minp = (cost, theta)
+ if min_cost[0] < cost:
+ min_cost = (cost, theta)
# calc best rectangle
- sin_s = np.sin(minp[1])
- cos_s = np.cos(minp[1])
+ sin_s = np.sin(min_cost[1])
+ cos_s = np.cos(min_cost[1])
- c1_s = X @ np.array([cos_s, sin_s]).T
- c2_s = X @ np.array([-sin_s, cos_s]).T
+ c1_s = xy @ np.array([cos_s, sin_s]).T
+ c2_s = xy @ np.array([-sin_s, cos_s]).T
rect = RectangleData()
rect.a[0] = cos_s
@@ -157,31 +173,31 @@ def _rectangle_search(self, x, y):
def _adoptive_range_segmentation(self, ox, oy):
# Setup initial cluster
- S = []
+ segment_list = []
for i, _ in enumerate(ox):
- C = set()
- R = self.R0 + self.Rd * np.linalg.norm([ox[i], oy[i]])
+ c = set()
+ r = self.R0 + self.Rd * np.linalg.norm([ox[i], oy[i]])
for j, _ in enumerate(ox):
- d = np.sqrt((ox[i] - ox[j])**2 + (oy[i] - oy[j])**2)
- if d <= R:
- C.add(j)
- S.append(C)
+ d = np.hypot(ox[i] - ox[j], oy[i] - oy[j])
+ if d <= r:
+ c.add(j)
+ segment_list.append(c)
# Merge cluster
- while 1:
+ while True:
no_change = True
- for (c1, c2) in list(itertools.permutations(range(len(S)), 2)):
- if S[c1] & S[c2]:
- S[c1] = (S[c1] | S.pop(c2))
+ for (c1, c2) in list(itertools.permutations(range(len(segment_list)), 2)):
+ if segment_list[c1] & segment_list[c2]:
+ segment_list[c1] = (segment_list[c1] | segment_list.pop(c2))
no_change = False
break
if no_change:
break
- return S
+ return segment_list
-class RectangleData():
+class RectangleData:
def __init__(self):
self.a = [None] * 4
@@ -207,7 +223,8 @@ def calc_rect_contour(self):
[self.a[3], self.a[0]], [self.b[3], self.b[0]], [self.c[3], self.c[0]])
self.rect_c_x[4], self.rect_c_y[4] = self.rect_c_x[0], self.rect_c_y[0]
- def calc_cross_point(self, a, b, c):
+ @staticmethod
+ def calc_cross_point(a, b, c):
x = (b[0] * -c[1] - b[1] * -c[0]) / (a[0] * b[1] - a[1] * b[0])
y = (a[1] * -c[0] - a[0] * -c[1]) / (a[0] * b[1] - a[1] * b[0])
return x, y
@@ -216,39 +233,43 @@ def calc_cross_point(self, a, b, c):
def main():
# simulation parameters
- simtime = 30.0 # simulation time
+ sim_time = 30.0 # simulation time
dt = 0.2 # time tick
- angle_reso = np.deg2rad(3.0) # sensor angle resolution
+ angle_resolution = np.deg2rad(3.0) # sensor angle resolution
v1 = VehicleSimulator(-10.0, 0.0, np.deg2rad(90.0),
0.0, 50.0 / 3.6, 3.0, 5.0)
v2 = VehicleSimulator(20.0, 10.0, np.deg2rad(180.0),
0.0, 50.0 / 3.6, 4.0, 10.0)
- lshapefitting = LShapeFitting()
+ l_shape_fitting = LShapeFitting()
lidar_sim = LidarSimulator()
time = 0.0
- while time <= simtime:
+ while time <= sim_time:
time += dt
v1.update(dt, 0.1, 0.0)
v2.update(dt, 0.1, -0.05)
- ox, oy = lidar_sim.get_observation_points([v1, v2], angle_reso)
+ ox, oy = lidar_sim.get_observation_points([v1, v2], angle_resolution)
- rects, idsets = lshapefitting.fitting(ox, oy)
+ rects, id_sets = l_shape_fitting.fitting(ox, oy)
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.axis("equal")
plt.plot(0.0, 0.0, "*r")
v1.plot()
v2.plot()
# Plot range observation
- for ids in idsets:
+ for ids in id_sets:
x = [ox[i] for i in range(len(ox)) if i in ids]
y = [oy[i] for i in range(len(ox)) if i in ids]
diff --git a/Mapping/rectangle_fitting/simulator.py b/Mapping/rectangle_fitting/simulator.py
index b21d4003a8..aa32ae1b1f 100644
--- a/Mapping/rectangle_fitting/simulator.py
+++ b/Mapping/rectangle_fitting/simulator.py
@@ -5,20 +5,25 @@
author: Atsushi Sakai
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import numpy as np
import matplotlib.pyplot as plt
import math
import random
+from utils.angle import rot_mat_2d
-class VehicleSimulator():
- def __init__(self, ix, iy, iyaw, iv, max_v, w, L):
- self.x = ix
- self.y = iy
- self.yaw = iyaw
- self.v = iv
+class VehicleSimulator:
+
+ def __init__(self, i_x, i_y, i_yaw, i_v, max_v, w, L):
+ self.x = i_x
+ self.y = i_y
+ self.yaw = i_yaw
+ self.v = i_v
self.max_v = max_v
self.W = w
self.L = L
@@ -40,10 +45,9 @@ def plot(self):
plt.plot(gx, gy, "--b")
def calc_global_contour(self):
- gx = [(ix * np.cos(self.yaw) + iy * np.sin(self.yaw)) +
- self.x for (ix, iy) in zip(self.vc_x, self.vc_y)]
- gy = [(ix * np.sin(self.yaw) - iy * np.cos(self.yaw)) +
- self.y for (ix, iy) in zip(self.vc_x, self.vc_y)]
+ gxy = np.stack([self.vc_x, self.vc_y]).T @ rot_mat_2d(self.yaw)
+ gx = gxy[:, 0] + self.x
+ gy = gxy[:, 1] + self.y
return gx, gy
@@ -67,78 +71,70 @@ def _calc_vehicle_contour(self):
self.vc_x.append(self.L / 2.0)
self.vc_y.append(self.W / 2.0)
- self.vc_x, self.vc_y = self._interporate(self.vc_x, self.vc_y)
+ self.vc_x, self.vc_y = self._interpolate(self.vc_x, self.vc_y)
- def _interporate(self, x, y):
+ @staticmethod
+ def _interpolate(x, y):
rx, ry = [], []
- dtheta = 0.05
+ d_theta = 0.05
for i in range(len(x) - 1):
- rx.extend([(1.0 - θ) * x[i] + θ * x[i + 1]
- for θ in np.arange(0.0, 1.0, dtheta)])
- ry.extend([(1.0 - θ) * y[i] + θ * y[i + 1]
- for θ in np.arange(0.0, 1.0, dtheta)])
+ rx.extend([(1.0 - theta) * x[i] + theta * x[i + 1]
+ for theta in np.arange(0.0, 1.0, d_theta)])
+ ry.extend([(1.0 - theta) * y[i] + theta * y[i + 1]
+ for theta in np.arange(0.0, 1.0, d_theta)])
- rx.extend([(1.0 - θ) * x[len(x) - 1] + θ * x[1]
- for θ in np.arange(0.0, 1.0, dtheta)])
- ry.extend([(1.0 - θ) * y[len(y) - 1] + θ * y[1]
- for θ in np.arange(0.0, 1.0, dtheta)])
+ rx.extend([(1.0 - theta) * x[len(x) - 1] + theta * x[1]
+ for theta in np.arange(0.0, 1.0, d_theta)])
+ ry.extend([(1.0 - theta) * y[len(y) - 1] + theta * y[1]
+ for theta in np.arange(0.0, 1.0, d_theta)])
return rx, ry
-class LidarSimulator():
+class LidarSimulator:
def __init__(self):
self.range_noise = 0.01
- def get_observation_points(self, vlist, angle_reso):
+ def get_observation_points(self, v_list, angle_resolution):
x, y, angle, r = [], [], [], []
# store all points
- for v in vlist:
+ for v in v_list:
gx, gy = v.calc_global_contour()
for vx, vy in zip(gx, gy):
- vangle = math.atan2(vy, vx)
+ v_angle = math.atan2(vy, vx)
vr = np.hypot(vx, vy) * random.uniform(1.0 - self.range_noise,
1.0 + self.range_noise)
x.append(vx)
y.append(vy)
- angle.append(vangle)
+ angle.append(v_angle)
r.append(vr)
# ray casting filter
- rx, ry = self.ray_casting_filter(x, y, angle, r, angle_reso)
+ rx, ry = self.ray_casting_filter(angle, r, angle_resolution)
return rx, ry
- def ray_casting_filter(self, xl, yl, thetal, rangel, angle_reso):
+ @staticmethod
+ def ray_casting_filter(theta_l, range_l, angle_resolution):
rx, ry = [], []
- rangedb = [float("inf") for _ in range(
- int(np.floor((np.pi * 2.0) / angle_reso)) + 1)]
+ range_db = [float("inf") for _ in range(
+ int(np.floor((np.pi * 2.0) / angle_resolution)) + 1)]
- for i in range(len(thetal)):
- angleid = int(round(thetal[i] / angle_reso))
+ for i in range(len(theta_l)):
+ angle_id = int(round(theta_l[i] / angle_resolution))
- if rangedb[angleid] > rangel[i]:
- rangedb[angleid] = rangel[i]
+ if range_db[angle_id] > range_l[i]:
+ range_db[angle_id] = range_l[i]
- for i in range(len(rangedb)):
- t = i * angle_reso
- if rangedb[i] != float("inf"):
- rx.append(rangedb[i] * np.cos(t))
- ry.append(rangedb[i] * np.sin(t))
+ for i in range(len(range_db)):
+ t = i * angle_resolution
+ if range_db[i] != float("inf"):
+ rx.append(range_db[i] * np.cos(t))
+ ry.append(range_db[i] * np.sin(t))
return rx, ry
-
-
-def main():
- print("start!!")
-
- print("done!!")
-
-
-if __name__ == '__main__':
- main()
diff --git a/MissionPlanning/BehaviorTree/behavior_tree.py b/MissionPlanning/BehaviorTree/behavior_tree.py
new file mode 100644
index 0000000000..9ad886aafb
--- /dev/null
+++ b/MissionPlanning/BehaviorTree/behavior_tree.py
@@ -0,0 +1,690 @@
+"""
+Behavior Tree
+
+author: Wang Zheng (@Aglargil)
+
+Reference:
+
+- [Behavior Tree](https://en.wikipedia.org/wiki/Behavior_tree_(artificial_intelligence,_robotics_and_control))
+"""
+
+import time
+import xml.etree.ElementTree as ET
+from enum import Enum
+
+
+class Status(Enum):
+ SUCCESS = "success"
+ FAILURE = "failure"
+ RUNNING = "running"
+
+
+class NodeType(Enum):
+ CONTROL_NODE = "ControlNode"
+ ACTION_NODE = "ActionNode"
+ DECORATOR_NODE = "DecoratorNode"
+
+
+class Node:
+ """
+ Base class for all nodes in a behavior tree.
+ """
+
+ def __init__(self, name):
+ self.name = name
+ self.status = None
+
+ def tick(self) -> Status:
+ """
+ Tick the node.
+
+ Returns:
+ Status: The status of the node.
+ """
+ raise ValueError("Node is not implemented")
+
+ def tick_and_set_status(self) -> Status:
+ """
+ Tick the node and set the status.
+
+ Returns:
+ Status: The status of the node.
+ """
+ self.status = self.tick()
+ return self.status
+
+ def reset(self):
+ """
+ Reset the node.
+ """
+ self.status = None
+
+ def reset_children(self):
+ """
+ Reset the children of the node.
+ """
+ pass
+
+
+class ControlNode(Node):
+ """
+ Base class for all control nodes in a behavior tree.
+
+ Control nodes manage the execution flow of their child nodes according to specific rules.
+ They typically have multiple children and determine which children to execute and in what order.
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+ self.children = []
+ self.type = NodeType.CONTROL_NODE
+
+ def not_set_children_raise_error(self):
+ if len(self.children) == 0:
+ raise ValueError("Children are not set")
+
+ def reset_children(self):
+ for child in self.children:
+ child.reset()
+
+
+class SequenceNode(ControlNode):
+ """
+ Executes child nodes in sequence until one fails or all succeed.
+
+ Returns:
+ - Returns FAILURE if any child returns FAILURE
+ - Returns SUCCESS when all children have succeeded
+ - Returns RUNNING when a child is still running or when moving to the next child
+
+ Example:
+ .. code-block:: xml
+
+
+
+
+
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+ self.current_child_index = 0
+
+ def tick(self) -> Status:
+ self.not_set_children_raise_error()
+
+ if self.current_child_index >= len(self.children):
+ self.reset_children()
+ return Status.SUCCESS
+ status = self.children[self.current_child_index].tick_and_set_status()
+ if status == Status.FAILURE:
+ self.reset_children()
+ return Status.FAILURE
+ elif status == Status.SUCCESS:
+ self.current_child_index += 1
+ return Status.RUNNING
+ elif status == Status.RUNNING:
+ return Status.RUNNING
+ else:
+ raise ValueError("Unknown status")
+
+
+class SelectorNode(ControlNode):
+ """
+ Executes child nodes in sequence until one succeeds or all fail.
+
+ Returns:
+ - Returns SUCCESS if any child returns SUCCESS
+ - Returns FAILURE when all children have failed
+ - Returns RUNNING when a child is still running or when moving to the next child
+
+ Examples:
+ .. code-block:: xml
+
+
+
+
+
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+ self.current_child_index = 0
+
+ def tick(self) -> Status:
+ self.not_set_children_raise_error()
+
+ if self.current_child_index >= len(self.children):
+ self.reset_children()
+ return Status.FAILURE
+ status = self.children[self.current_child_index].tick_and_set_status()
+ if status == Status.SUCCESS:
+ self.reset_children()
+ return Status.SUCCESS
+ elif status == Status.FAILURE:
+ self.current_child_index += 1
+ return Status.RUNNING
+ elif status == Status.RUNNING:
+ return Status.RUNNING
+ else:
+ raise ValueError("Unknown status")
+
+
+class WhileDoElseNode(ControlNode):
+ """
+ Conditional execution node with three parts: condition, do, and optional else.
+
+ Returns:
+ First executes the condition node (child[0])
+ If condition succeeds, executes do node (child[1]) and returns RUNNING
+ If condition fails, executes else node (child[2]) if present and returns result of else node
+ If condition fails and there is no else node, returns SUCCESS
+
+ Example:
+ .. code-block:: xml
+
+
+
+
+
+
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+
+ def tick(self) -> Status:
+ if len(self.children) != 3 and len(self.children) != 2:
+ raise ValueError("WhileDoElseNode must have exactly 3 or 2 children")
+
+ condition_node = self.children[0]
+ do_node = self.children[1]
+ else_node = self.children[2] if len(self.children) == 3 else None
+
+ condition_status = condition_node.tick_and_set_status()
+ if condition_status == Status.SUCCESS:
+ do_node.tick_and_set_status()
+ return Status.RUNNING
+ elif condition_status == Status.FAILURE:
+ if else_node is not None:
+ else_status = else_node.tick_and_set_status()
+ if else_status == Status.SUCCESS:
+ self.reset_children()
+ return Status.SUCCESS
+ elif else_status == Status.FAILURE:
+ self.reset_children()
+ return Status.FAILURE
+ elif else_status == Status.RUNNING:
+ return Status.RUNNING
+ else:
+ raise ValueError("Unknown status")
+ else:
+ self.reset_children()
+ return Status.SUCCESS
+ else:
+ raise ValueError("Unknown status")
+
+
+class ActionNode(Node):
+ """
+ Base class for all action nodes in a behavior tree.
+
+ Action nodes are responsible for performing specific tasks or actions.
+ They do not have children and are typically used to execute logic or operations.
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+ self.type = NodeType.ACTION_NODE
+
+
+class SleepNode(ActionNode):
+ """
+ Sleep node that sleeps for a specified duration.
+
+ Returns:
+ Returns SUCCESS after the specified duration has passed
+ Returns RUNNING if the duration has not yet passed
+
+ Example:
+ .. code-block:: xml
+
+
+ """
+
+ def __init__(self, name, duration):
+ super().__init__(name)
+ self.duration = duration
+ self.start_time = None
+
+ def tick(self) -> Status:
+ if self.start_time is None:
+ self.start_time = time.time()
+ if time.time() - self.start_time > self.duration:
+ return Status.SUCCESS
+ return Status.RUNNING
+
+
+class EchoNode(ActionNode):
+ """
+ Echo node that prints a message to the console.
+
+ Returns:
+ Returns SUCCESS after the message has been printed
+
+ Example:
+ .. code-block:: xml
+
+
+ """
+
+ def __init__(self, name, message):
+ super().__init__(name)
+ self.message = message
+
+ def tick(self) -> Status:
+ print(self.name, self.message)
+ return Status.SUCCESS
+
+
+class DecoratorNode(Node):
+ """
+ Base class for all decorator nodes in a behavior tree.
+
+ Decorator nodes modify the behavior of their child node.
+ They must have a single child and can alter the status of the child node.
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+ self.type = NodeType.DECORATOR_NODE
+ self.child = None
+
+ def not_set_child_raise_error(self):
+ if self.child is None:
+ raise ValueError("Child is not set")
+
+ def reset_children(self):
+ self.child.reset()
+
+
+class InverterNode(DecoratorNode):
+ """
+ Inverter node that inverts the status of its child node.
+
+ Returns:
+ - Returns SUCCESS if the child returns FAILURE
+ - Returns FAILURE if the child returns SUCCESS
+ - Returns RUNNING if the child returns RUNNING
+
+ Examples:
+ .. code-block:: xml
+
+
+
+
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+
+ def tick(self) -> Status:
+ self.not_set_child_raise_error()
+ status = self.child.tick_and_set_status()
+ return Status.SUCCESS if status == Status.FAILURE else Status.FAILURE
+
+
+class TimeoutNode(DecoratorNode):
+ """
+ Timeout node that fails if the child node takes too long to execute
+
+ Returns:
+ - FAILURE: If the timeout duration has been exceeded
+ - Child's status: Otherwise, passes through the status of the child node
+
+ Example:
+ .. code-block:: xml
+
+
+
+
+ """
+
+ def __init__(self, name, timeout):
+ super().__init__(name)
+ self.timeout = timeout
+ self.start_time = None
+
+ def tick(self) -> Status:
+ self.not_set_child_raise_error()
+ if self.start_time is None:
+ self.start_time = time.time()
+ if time.time() - self.start_time > self.timeout:
+ return Status.FAILURE
+ print(f"{self.name} is running")
+ return self.child.tick_and_set_status()
+
+
+class DelayNode(DecoratorNode):
+ """
+ Delay node that delays the execution of its child node for a specified duration.
+
+ Returns:
+ - Returns RUNNING if the duration has not yet passed
+ - Returns child's status after the duration has passed
+
+ Example:
+ .. code-block:: xml
+
+
+
+
+ """
+
+ def __init__(self, name, delay):
+ super().__init__(name)
+ self.delay = delay
+ self.start_time = None
+
+ def tick(self) -> Status:
+ self.not_set_child_raise_error()
+ if self.start_time is None:
+ self.start_time = time.time()
+ if time.time() - self.start_time > self.delay:
+ return self.child.tick_and_set_status()
+ return Status.RUNNING
+
+
+class ForceSuccessNode(DecoratorNode):
+ """
+ ForceSuccess node that always returns SUCCESS.
+
+ Returns:
+ - Returns RUNNING if the child returns RUNNING
+ - Returns SUCCESS if the child returns SUCCESS or FAILURE
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+
+ def tick(self) -> Status:
+ self.not_set_child_raise_error()
+ status = self.child.tick_and_set_status()
+ if status == Status.FAILURE:
+ return Status.SUCCESS
+ return status
+
+
+class ForceFailureNode(DecoratorNode):
+ """
+ ForceFailure node that always returns FAILURE.
+
+ Returns:
+ - Returns RUNNING if the child returns RUNNING
+ - Returns FAILURE if the child returns SUCCESS or FAILURE
+ """
+
+ def __init__(self, name):
+ super().__init__(name)
+
+ def tick(self) -> Status:
+ self.not_set_child_raise_error()
+ status = self.child.tick_and_set_status()
+ if status == Status.SUCCESS:
+ return Status.FAILURE
+ return status
+
+
+class BehaviorTree:
+ """
+ Behavior tree class that manages the execution of a behavior tree.
+ """
+
+ def __init__(self, root):
+ self.root = root
+
+ def tick(self):
+ """
+ Tick once on the behavior tree.
+ """
+ self.root.tick_and_set_status()
+
+ def reset(self):
+ """
+ Reset the behavior tree.
+ """
+ self.root.reset()
+
+ def tick_while_running(self, interval=None, enable_print=True):
+ """
+ Tick the behavior tree while it is running.
+
+ Args:
+ interval (float, optional): The interval between ticks. Defaults to None.
+ enable_print (bool, optional): Whether to print the behavior tree. Defaults to True.
+ """
+ while self.root.tick_and_set_status() == Status.RUNNING:
+ if enable_print:
+ self.print_tree()
+ if interval is not None:
+ time.sleep(interval)
+ if enable_print:
+ self.print_tree()
+
+ def to_text(self, root, indent=0):
+ """
+ Recursively convert the behavior tree to a text representation.
+ """
+ current_text = ""
+ if root.status == Status.RUNNING:
+ # yellow
+ current_text = "\033[93m" + root.name + "\033[0m"
+ elif root.status == Status.SUCCESS:
+ # green
+ current_text = "\033[92m" + root.name + "\033[0m"
+ elif root.status == Status.FAILURE:
+ # red
+ current_text = "\033[91m" + root.name + "\033[0m"
+ else:
+ current_text = root.name
+ if root.type == NodeType.CONTROL_NODE:
+ current_text = " " * indent + "[" + current_text + "]\n"
+ for child in root.children:
+ current_text += self.to_text(child, indent + 2)
+ elif root.type == NodeType.DECORATOR_NODE:
+ current_text = " " * indent + "(" + current_text + ")\n"
+ current_text += self.to_text(root.child, indent + 2)
+ elif root.type == NodeType.ACTION_NODE:
+ current_text = " " * indent + "<" + current_text + ">\n"
+ return current_text
+
+ def print_tree(self):
+ """
+ Print the behavior tree.
+
+ Node print format:
+ Action:
+ Decorator: (Decorator)
+ Control: [Control]
+
+ Node status colors:
+ Yellow: RUNNING
+ Green: SUCCESS
+ Red: FAILURE
+ """
+ text = self.to_text(self.root)
+ text = text.strip()
+ print("\033[94m" + "Behavior Tree" + "\033[0m")
+ print(text)
+ print("\033[94m" + "Behavior Tree" + "\033[0m")
+
+
+class BehaviorTreeFactory:
+ """
+ Factory class for creating behavior trees from XML strings.
+ """
+
+ def __init__(self):
+ self.node_builders = {}
+ # Control nodes
+ self.register_node_builder(
+ "Sequence",
+ lambda node: SequenceNode(node.attrib.get("name", SequenceNode.__name__)),
+ )
+ self.register_node_builder(
+ "Selector",
+ lambda node: SelectorNode(node.attrib.get("name", SelectorNode.__name__)),
+ )
+ self.register_node_builder(
+ "WhileDoElse",
+ lambda node: WhileDoElseNode(
+ node.attrib.get("name", WhileDoElseNode.__name__)
+ ),
+ )
+ # Decorator nodes
+ self.register_node_builder(
+ "Inverter",
+ lambda node: InverterNode(node.attrib.get("name", InverterNode.__name__)),
+ )
+ self.register_node_builder(
+ "Timeout",
+ lambda node: TimeoutNode(
+ node.attrib.get("name", SelectorNode.__name__),
+ float(node.attrib["sec"]),
+ ),
+ )
+ self.register_node_builder(
+ "Delay",
+ lambda node: DelayNode(
+ node.attrib.get("name", DelayNode.__name__),
+ float(node.attrib["sec"]),
+ ),
+ )
+ self.register_node_builder(
+ "ForceSuccess",
+ lambda node: ForceSuccessNode(
+ node.attrib.get("name", ForceSuccessNode.__name__)
+ ),
+ )
+ self.register_node_builder(
+ "ForceFailure",
+ lambda node: ForceFailureNode(
+ node.attrib.get("name", ForceFailureNode.__name__)
+ ),
+ )
+ # Action nodes
+ self.register_node_builder(
+ "Sleep",
+ lambda node: SleepNode(
+ node.attrib.get("name", SleepNode.__name__),
+ float(node.attrib["sec"]),
+ ),
+ )
+ self.register_node_builder(
+ "Echo",
+ lambda node: EchoNode(
+ node.attrib.get("name", EchoNode.__name__),
+ node.attrib["message"],
+ ),
+ )
+
+ def register_node_builder(self, node_name, builder):
+ """
+ Register a builder for a node
+
+ Args:
+ node_name (str): The name of the node.
+ builder (function): The builder function.
+
+ Example:
+ .. code-block:: python
+
+ factory = BehaviorTreeFactory()
+ factory.register_node_builder(
+ "MyNode",
+ lambda node: MyNode(
+ node.attrib.get("name", MyNode.__name__),
+ node.attrib["my_param"],
+ ),
+ )
+ """
+ self.node_builders[node_name] = builder
+
+ def build_node(self, node):
+ """
+ Build a node from an XML element.
+
+ Args:
+ node (Element): The XML element to build the node from.
+
+ Returns:
+ BehaviorTree Node: the built node
+ """
+ if node.tag in self.node_builders:
+ root = self.node_builders[node.tag](node)
+ if root.type == NodeType.CONTROL_NODE:
+ if len(node) <= 0:
+ raise ValueError(f"{root.name} Control node must have children")
+ for child in node:
+ root.children.append(self.build_node(child))
+ elif root.type == NodeType.DECORATOR_NODE:
+ if len(node) != 1:
+ raise ValueError(
+ f"{root.name} Decorator node must have exactly one child"
+ )
+ root.child = self.build_node(node[0])
+ elif root.type == NodeType.ACTION_NODE:
+ if len(node) != 0:
+ raise ValueError(f"{root.name} Action node must have no children")
+ return root
+ else:
+ raise ValueError(f"Unknown node type: {node.tag}")
+
+ def build_tree(self, xml_string):
+ """
+ Build a behavior tree from an XML string.
+
+ Args:
+ xml_string (str): The XML string containing the behavior tree.
+
+ Returns:
+ BehaviorTree: The behavior tree.
+ """
+ xml_tree = ET.fromstring(xml_string)
+ root = self.build_node(xml_tree)
+ return BehaviorTree(root)
+
+ def build_tree_from_file(self, file_path):
+ """
+ Build a behavior tree from a file.
+
+ Args:
+ file_path (str): The path to the file containing the behavior tree.
+
+ Returns:
+ BehaviorTree: The behavior tree.
+ """
+ with open(file_path) as file:
+ xml_string = file.read()
+ return self.build_tree(xml_string)
+
+
+xml_string = """
+
+
+
+
+
+
+
+ """
+
+
+def main():
+ factory = BehaviorTreeFactory()
+ tree = factory.build_tree(xml_string)
+ tree.tick_while_running()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/MissionPlanning/BehaviorTree/robot_behavior_case.py b/MissionPlanning/BehaviorTree/robot_behavior_case.py
new file mode 100644
index 0000000000..6c39aa76b2
--- /dev/null
+++ b/MissionPlanning/BehaviorTree/robot_behavior_case.py
@@ -0,0 +1,247 @@
+"""
+Robot Behavior Tree Case
+
+This file demonstrates how to use a behavior tree to control robot behavior.
+"""
+
+from behavior_tree import (
+ BehaviorTreeFactory,
+ Status,
+ ActionNode,
+)
+import time
+import random
+import os
+
+
+class CheckBatteryNode(ActionNode):
+ """
+ Node to check robot battery level
+
+ If battery level is below threshold, returns FAILURE, otherwise returns SUCCESS
+ """
+
+ def __init__(self, name, threshold=20):
+ super().__init__(name)
+ self.threshold = threshold
+ self.battery_level = 100 # Initial battery level is 100%
+
+ def tick(self):
+ # Simulate battery level decreasing
+ self.battery_level -= random.randint(1, 5)
+ print(f"Current battery level: {self.battery_level}%")
+
+ if self.battery_level <= self.threshold:
+ return Status.FAILURE
+ return Status.SUCCESS
+
+
+class ChargeBatteryNode(ActionNode):
+ """
+ Node to charge the robot's battery
+ """
+
+ def __init__(self, name, charge_rate=10):
+ super().__init__(name)
+ self.charge_rate = charge_rate
+ self.charging_time = 0
+
+ def tick(self):
+ # Simulate charging process
+ if self.charging_time == 0:
+ print("Starting to charge...")
+
+ self.charging_time += 1
+ charge_amount = self.charge_rate * self.charging_time
+
+ if charge_amount >= 100:
+ print("Charging complete! Battery level: 100%")
+ self.charging_time = 0
+ return Status.SUCCESS
+ else:
+ print(f"Charging in progress... Battery level: {min(charge_amount, 100)}%")
+ return Status.RUNNING
+
+
+class MoveToPositionNode(ActionNode):
+ """
+ Node to move to a specified position
+ """
+
+ def __init__(self, name, position, move_duration=2):
+ super().__init__(name)
+ self.position = position
+ self.move_duration = move_duration
+ self.start_time = None
+
+ def tick(self):
+ if self.start_time is None:
+ self.start_time = time.time()
+ print(f"Starting movement to position {self.position}")
+
+ elapsed_time = time.time() - self.start_time
+
+ if elapsed_time >= self.move_duration:
+ print(f"Arrived at position {self.position}")
+ self.start_time = None
+ return Status.SUCCESS
+ else:
+ print(
+ f"Moving to position {self.position}... {int(elapsed_time / self.move_duration * 100)}% complete"
+ )
+ return Status.RUNNING
+
+
+class DetectObstacleNode(ActionNode):
+ """
+ Node to detect obstacles
+ """
+
+ def __init__(self, name, obstacle_probability=0.3):
+ super().__init__(name)
+ self.obstacle_probability = obstacle_probability
+
+ def tick(self):
+ # Use random probability to simulate obstacle detection
+ if random.random() < self.obstacle_probability:
+ print("Obstacle detected!")
+ return Status.SUCCESS
+ else:
+ print("No obstacle detected")
+ return Status.FAILURE
+
+
+class AvoidObstacleNode(ActionNode):
+ """
+ Node to avoid obstacles
+ """
+
+ def __init__(self, name, avoid_duration=1.5):
+ super().__init__(name)
+ self.avoid_duration = avoid_duration
+ self.start_time = None
+
+ def tick(self):
+ if self.start_time is None:
+ self.start_time = time.time()
+ print("Starting obstacle avoidance...")
+
+ elapsed_time = time.time() - self.start_time
+
+ if elapsed_time >= self.avoid_duration:
+ print("Obstacle avoidance complete")
+ self.start_time = None
+ return Status.SUCCESS
+ else:
+ print("Avoiding obstacle...")
+ return Status.RUNNING
+
+
+class PerformTaskNode(ActionNode):
+ """
+ Node to perform a specific task
+ """
+
+ def __init__(self, name, task_name, task_duration=3):
+ super().__init__(name)
+ self.task_name = task_name
+ self.task_duration = task_duration
+ self.start_time = None
+
+ def tick(self):
+ if self.start_time is None:
+ self.start_time = time.time()
+ print(f"Starting task: {self.task_name}")
+
+ elapsed_time = time.time() - self.start_time
+
+ if elapsed_time >= self.task_duration:
+ print(f"Task complete: {self.task_name}")
+ self.start_time = None
+ return Status.SUCCESS
+ else:
+ print(
+ f"Performing task: {self.task_name}... {int(elapsed_time / self.task_duration * 100)}% complete"
+ )
+ return Status.RUNNING
+
+
+def create_robot_behavior_tree():
+ """
+ Create robot behavior tree
+ """
+
+ factory = BehaviorTreeFactory()
+
+ # Register custom nodes
+ factory.register_node_builder(
+ "CheckBattery",
+ lambda node: CheckBatteryNode(
+ node.attrib.get("name", "CheckBattery"),
+ int(node.attrib.get("threshold", "20")),
+ ),
+ )
+
+ factory.register_node_builder(
+ "ChargeBattery",
+ lambda node: ChargeBatteryNode(
+ node.attrib.get("name", "ChargeBattery"),
+ int(node.attrib.get("charge_rate", "10")),
+ ),
+ )
+
+ factory.register_node_builder(
+ "MoveToPosition",
+ lambda node: MoveToPositionNode(
+ node.attrib.get("name", "MoveToPosition"),
+ node.attrib.get("position", "Unknown Position"),
+ float(node.attrib.get("move_duration", "2")),
+ ),
+ )
+
+ factory.register_node_builder(
+ "DetectObstacle",
+ lambda node: DetectObstacleNode(
+ node.attrib.get("name", "DetectObstacle"),
+ float(node.attrib.get("obstacle_probability", "0.3")),
+ ),
+ )
+
+ factory.register_node_builder(
+ "AvoidObstacle",
+ lambda node: AvoidObstacleNode(
+ node.attrib.get("name", "AvoidObstacle"),
+ float(node.attrib.get("avoid_duration", "1.5")),
+ ),
+ )
+
+ factory.register_node_builder(
+ "PerformTask",
+ lambda node: PerformTaskNode(
+ node.attrib.get("name", "PerformTask"),
+ node.attrib.get("task_name", "Unknown Task"),
+ float(node.attrib.get("task_duration", "3")),
+ ),
+ )
+ # Read XML from file
+ xml_path = os.path.join(os.path.dirname(__file__), "robot_behavior_tree.xml")
+ return factory.build_tree_from_file(xml_path)
+
+
+def main():
+ """
+ Main function: Create and run the robot behavior tree
+ """
+ print("Creating robot behavior tree...")
+ tree = create_robot_behavior_tree()
+
+ print("\nStarting robot behavior tree execution...\n")
+ # Run for a period of time or until completion
+
+ tree.tick_while_running(interval=0.01)
+
+ print("\nBehavior tree execution complete!")
+
+
+if __name__ == "__main__":
+ main()
diff --git a/MissionPlanning/BehaviorTree/robot_behavior_tree.xml b/MissionPlanning/BehaviorTree/robot_behavior_tree.xml
new file mode 100644
index 0000000000..0bca76a3ff
--- /dev/null
+++ b/MissionPlanning/BehaviorTree/robot_behavior_tree.xml
@@ -0,0 +1,57 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/MissionPlanning/StateMachine/robot_behavior_case.py b/MissionPlanning/StateMachine/robot_behavior_case.py
new file mode 100644
index 0000000000..03ee60ae9f
--- /dev/null
+++ b/MissionPlanning/StateMachine/robot_behavior_case.py
@@ -0,0 +1,111 @@
+"""
+A case study of robot behavior using state machine
+
+author: Wang Zheng (@Aglargil)
+"""
+
+from state_machine import StateMachine
+
+
+class Robot:
+ def __init__(self):
+ self.battery = 100
+ self.task_progress = 0
+
+ # Initialize state machine
+ self.machine = StateMachine("robot_sm", self)
+
+ # Add state transition rules
+ self.machine.add_transition(
+ src_state="patrolling",
+ event="detect_task",
+ dst_state="executing_task",
+ guard=None,
+ action=None,
+ )
+
+ self.machine.add_transition(
+ src_state="executing_task",
+ event="task_complete",
+ dst_state="patrolling",
+ guard=None,
+ action="reset_task",
+ )
+
+ self.machine.add_transition(
+ src_state="executing_task",
+ event="low_battery",
+ dst_state="returning_to_base",
+ guard="is_battery_low",
+ )
+
+ self.machine.add_transition(
+ src_state="returning_to_base",
+ event="reach_base",
+ dst_state="charging",
+ guard=None,
+ action=None,
+ )
+
+ self.machine.add_transition(
+ src_state="charging",
+ event="charge_complete",
+ dst_state="patrolling",
+ guard=None,
+ action="battery_full",
+ )
+
+ # Set initial state
+ self.machine.set_current_state("patrolling")
+
+ def is_battery_low(self):
+ """Battery level check condition"""
+ return self.battery < 30
+
+ def reset_task(self):
+ """Reset task progress"""
+ self.task_progress = 0
+ print("[Action] Task progress has been reset")
+
+ # Modify state entry callback naming convention (add state_ prefix)
+ def on_enter_executing_task(self):
+ print("\n------ Start Executing Task ------")
+ print(f"Current battery: {self.battery}%")
+ while self.machine.get_current_state().name == "executing_task":
+ self.task_progress += 10
+ self.battery -= 25
+ print(
+ f"Task progress: {self.task_progress}%, Remaining battery: {self.battery}%"
+ )
+
+ if self.task_progress >= 100:
+ self.machine.process("task_complete")
+ break
+ elif self.is_battery_low():
+ self.machine.process("low_battery")
+ break
+
+ def on_enter_returning_to_base(self):
+ print("\nLow battery, returning to charging station...")
+ self.machine.process("reach_base")
+
+ def on_enter_charging(self):
+ print("\n------ Charging ------")
+ self.battery = 100
+ print("Charging complete!")
+ self.machine.process("charge_complete")
+
+
+# Keep the test section structure the same, only modify the trigger method
+if __name__ == "__main__":
+ robot = Robot()
+ print(robot.machine.generate_plantuml())
+
+ print(f"Initial state: {robot.machine.get_current_state().name}")
+ print("------------")
+
+ # Trigger task detection event
+ robot.machine.process("detect_task")
+
+ print("\n------------")
+ print(f"Final state: {robot.machine.get_current_state().name}")
diff --git a/MissionPlanning/StateMachine/state_machine.py b/MissionPlanning/StateMachine/state_machine.py
new file mode 100644
index 0000000000..454759236e
--- /dev/null
+++ b/MissionPlanning/StateMachine/state_machine.py
@@ -0,0 +1,294 @@
+"""
+State Machine
+
+author: Wang Zheng (@Aglargil)
+
+Reference:
+
+- [State Machine]
+(https://en.wikipedia.org/wiki/Finite-state_machine)
+"""
+
+import string
+from urllib.request import urlopen, Request
+from base64 import b64encode
+from zlib import compress
+from io import BytesIO
+from collections.abc import Callable
+from matplotlib.image import imread
+from matplotlib import pyplot as plt
+
+
+def deflate_and_encode(plantuml_text):
+ """
+ zlib compress the plantuml text and encode it for the plantuml server.
+
+ Reference https://plantuml.com/en/text-encoding
+ """
+ plantuml_alphabet = (
+ string.digits + string.ascii_uppercase + string.ascii_lowercase + "-_"
+ )
+ base64_alphabet = (
+ string.ascii_uppercase + string.ascii_lowercase + string.digits + "+/"
+ )
+ b64_to_plantuml = bytes.maketrans(
+ base64_alphabet.encode("utf-8"), plantuml_alphabet.encode("utf-8")
+ )
+ zlibbed_str = compress(plantuml_text.encode("utf-8"))
+ compressed_string = zlibbed_str[2:-4]
+ return b64encode(compressed_string).translate(b64_to_plantuml).decode("utf-8")
+
+
+class State:
+ def __init__(self, name, on_enter=None, on_exit=None):
+ self.name = name
+ self.on_enter = on_enter
+ self.on_exit = on_exit
+
+ def enter(self):
+ print(f"entering <{self.name}>")
+ if self.on_enter:
+ self.on_enter()
+
+ def exit(self):
+ print(f"exiting <{self.name}>")
+ if self.on_exit:
+ self.on_exit()
+
+
+class StateMachine:
+ def __init__(self, name: str, model=object):
+ """Initialize the state machine.
+
+ Args:
+ name (str): Name of the state machine.
+ model (object, optional): Model object used to automatically look up callback functions
+ for states and transitions:
+ State callbacks: Automatically searches for 'on_enter_' and 'on_exit_' methods.
+ Transition callbacks: When action or guard parameters are strings, looks up corresponding methods in the model.
+
+ Example:
+ >>> class MyModel:
+ ... def on_enter_idle(self):
+ ... print("Entering idle state")
+ ... def on_exit_idle(self):
+ ... print("Exiting idle state")
+ ... def can_start(self):
+ ... return True
+ ... def on_start(self):
+ ... print("Starting operation")
+ >>> model = MyModel()
+ >>> machine = StateMachine("my_machine", model)
+ """
+ self._name = name
+ self._states = {}
+ self._events = {}
+ self._transition_table = {}
+ self._model = model
+ self._state: State = None
+
+ def _register_event(self, event: str):
+ self._events[event] = event
+
+ def _get_state(self, name):
+ return self._states[name]
+
+ def _get_event(self, name):
+ return self._events[name]
+
+ def _has_event(self, event: str):
+ return event in self._events
+
+ def add_transition(
+ self,
+ src_state: str | State,
+ event: str,
+ dst_state: str | State,
+ guard: str | Callable = None,
+ action: str | Callable = None,
+ ) -> None:
+ """Add a transition to the state machine.
+
+ Args:
+ src_state (str | State): The source state where the transition begins.
+ Can be either a state name or a State object.
+ event (str): The event that triggers this transition.
+ dst_state (str | State): The destination state where the transition ends.
+ Can be either a state name or a State object.
+ guard (str | Callable, optional): Guard condition for the transition.
+ If callable: Function that returns bool.
+ If str: Name of a method in the model class.
+ If returns True: Transition proceeds.
+ If returns False: Transition is skipped.
+ action (str | Callable, optional): Action to execute during transition.
+ If callable: Function to execute.
+ If str: Name of a method in the model class.
+ Executed after guard passes and before entering new state.
+
+ Example:
+ >>> machine.add_transition(
+ ... src_state="idle",
+ ... event="start",
+ ... dst_state="running",
+ ... guard="can_start",
+ ... action="on_start"
+ ... )
+ """
+ # Convert string parameters to objects if necessary
+ self.register_state(src_state)
+ self._register_event(event)
+ self.register_state(dst_state)
+
+ def get_state_obj(state):
+ return state if isinstance(state, State) else self._get_state(state)
+
+ def get_callable(func):
+ return func if callable(func) else getattr(self._model, func, None)
+
+ src_state_obj = get_state_obj(src_state)
+ dst_state_obj = get_state_obj(dst_state)
+
+ guard_func = get_callable(guard) if guard else None
+ action_func = get_callable(action) if action else None
+ self._transition_table[(src_state_obj.name, event)] = (
+ dst_state_obj,
+ guard_func,
+ action_func,
+ )
+
+ def state_transition(self, src_state: State, event: str):
+ if (src_state.name, event) not in self._transition_table:
+ raise ValueError(
+ f"|{self._name}| invalid transition: <{src_state.name}> : [{event}]"
+ )
+
+ dst_state, guard, action = self._transition_table[(src_state.name, event)]
+
+ def call_guard(guard):
+ if callable(guard):
+ return guard()
+ else:
+ return True
+
+ def call_action(action):
+ if callable(action):
+ action()
+
+ if call_guard(guard):
+ call_action(action)
+ if src_state.name != dst_state.name:
+ print(
+ f"|{self._name}| transitioning from <{src_state.name}> to <{dst_state.name}>"
+ )
+ src_state.exit()
+ self._state = dst_state
+ dst_state.enter()
+ else:
+ print(
+ f"|{self._name}| skipping transition from <{src_state.name}> to <{dst_state.name}> because guard failed"
+ )
+
+ def register_state(self, state: str | State, on_enter=None, on_exit=None):
+ """Register a state in the state machine.
+
+ Args:
+ state (str | State): The state to register. Can be either a string (state name)
+ or a State object.
+ on_enter (Callable, optional): Callback function to be executed when entering the state.
+ If state is a string and on_enter is None, it will look for
+ a method named 'on_enter_' in the model.
+ on_exit (Callable, optional): Callback function to be executed when exiting the state.
+ If state is a string and on_exit is None, it will look for
+ a method named 'on_exit_' in the model.
+ Example:
+ >>> machine.register_state("idle", on_enter=on_enter_idle, on_exit=on_exit_idle)
+ >>> machine.register_state(State("running", on_enter=on_enter_running, on_exit=on_exit_running))
+ """
+ if isinstance(state, str):
+ if on_enter is None:
+ on_enter = getattr(self._model, "on_enter_" + state, None)
+ if on_exit is None:
+ on_exit = getattr(self._model, "on_exit_" + state, None)
+ self._states[state] = State(state, on_enter, on_exit)
+ return
+
+ self._states[state.name] = state
+
+ def set_current_state(self, state: State | str):
+ if isinstance(state, str):
+ self._state = self._get_state(state)
+ else:
+ self._state = state
+
+ def get_current_state(self):
+ return self._state
+
+ def process(self, event: str) -> None:
+ """Process an event in the state machine.
+
+ Args:
+ event: Event name.
+
+ Example:
+ >>> machine.process("start")
+ """
+ if self._state is None:
+ raise ValueError("State machine is not initialized")
+
+ if self._has_event(event):
+ self.state_transition(self._state, event)
+ else:
+ raise ValueError(f"Invalid event: {event}")
+
+ def generate_plantuml(self) -> str:
+ """Generate PlantUML state diagram representation of the state machine.
+
+ Returns:
+ str: PlantUML state diagram code.
+ """
+ if self._state is None:
+ raise ValueError("State machine is not initialized")
+
+ plant_uml = ["@startuml"]
+ plant_uml.append("[*] --> " + self._state.name)
+
+ # Generate transitions
+ for (src_state, event), (
+ dst_state,
+ guard,
+ action,
+ ) in self._transition_table.items():
+ transition = f"{src_state} --> {dst_state.name} : {event}"
+
+ # Add guard and action if present
+ conditions = []
+ if guard:
+ guard_name = guard.__name__ if callable(guard) else guard
+ conditions.append(f"[{guard_name}]")
+ if action:
+ action_name = action.__name__ if callable(action) else action
+ conditions.append(f"/ {action_name}")
+
+ if conditions:
+ transition += "\\n" + " ".join(conditions)
+
+ plant_uml.append(transition)
+
+ plant_uml.append("@enduml")
+ plant_uml_text = "\n".join(plant_uml)
+
+ try:
+ url = f"http://www.plantuml.com/plantuml/img/{deflate_and_encode(plant_uml_text)}"
+ headers = {"User-Agent": "Mozilla/5.0"}
+ request = Request(url, headers=headers)
+
+ with urlopen(request) as response:
+ content = response.read()
+
+ plt.imshow(imread(BytesIO(content), format="png"))
+ plt.axis("off")
+ plt.show()
+ except Exception as e:
+ print(f"Error showing PlantUML: {e}")
+
+ return plant_uml_text
diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py
index ee14a94f3a..6d20350432 100644
--- a/PathPlanning/AStar/a_star.py
+++ b/PathPlanning/AStar/a_star.py
@@ -9,78 +9,95 @@
"""
-import matplotlib.pyplot as plt
import math
+import matplotlib.pyplot as plt
+
show_animation = True
class AStarPlanner:
- def __init__(self, ox, oy, reso, rr):
+ def __init__(self, ox, oy, resolution, rr):
"""
Initialize grid map for a star planning
ox: x position list of Obstacles [m]
oy: y position list of Obstacles [m]
- reso: grid resolution [m]
+ resolution: grid resolution [m]
rr: robot radius[m]
"""
- self.reso = reso
+ self.resolution = resolution
self.rr = rr
- self.calc_obstacle_map(ox, oy)
+ self.min_x, self.min_y = 0, 0
+ self.max_x, self.max_y = 0, 0
+ self.obstacle_map = None
+ self.x_width, self.y_width = 0, 0
self.motion = self.get_motion_model()
+ self.calc_obstacle_map(ox, oy)
class Node:
- def __init__(self, x, y, cost, pind):
+ def __init__(self, x, y, cost, parent_index):
self.x = x # index of grid
self.y = y # index of grid
self.cost = cost
- self.pind = pind
+ self.parent_index = parent_index
def __str__(self):
- return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
def planning(self, sx, sy, gx, gy):
"""
A star path search
input:
- sx: start x position [m]
- sy: start y position [m]
- gx: goal x position [m]
+ s_x: start x position [m]
+ s_y: start y position [m]
gx: goal x position [m]
+ gy: goal y position [m]
output:
rx: x position list of the final path
ry: y position list of the final path
"""
- nstart = self.Node(self.calc_xyindex(sx, self.minx),
- self.calc_xyindex(sy, self.miny), 0.0, -1)
- ngoal = self.Node(self.calc_xyindex(gx, self.minx),
- self.calc_xyindex(gy, self.miny), 0.0, -1)
+ start_node = self.Node(self.calc_xy_index(sx, self.min_x),
+ self.calc_xy_index(sy, self.min_y), 0.0, -1)
+ goal_node = self.Node(self.calc_xy_index(gx, self.min_x),
+ self.calc_xy_index(gy, self.min_y), 0.0, -1)
open_set, closed_set = dict(), dict()
- open_set[self.calc_grid_index(nstart)] = nstart
+ open_set[self.calc_grid_index(start_node)] = start_node
+
+ while True:
+ if len(open_set) == 0:
+ print("Open set is empty..")
+ break
- while 1:
c_id = min(
- open_set, key=lambda o: open_set[o].cost + self.calc_heuristic(ngoal, open_set[o]))
+ open_set,
+ key=lambda o: open_set[o].cost + self.calc_heuristic(goal_node,
+ open_set[
+ o]))
current = open_set[c_id]
# show graph
if show_animation: # pragma: no cover
- plt.plot(self.calc_grid_position(current.x, self.minx),
- self.calc_grid_position(current.y, self.miny), "xc")
+ plt.plot(self.calc_grid_position(current.x, self.min_x),
+ self.calc_grid_position(current.y, self.min_y), "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(
+ 0) if event.key == 'escape' else None])
if len(closed_set.keys()) % 10 == 0:
plt.pause(0.001)
- if current.x == ngoal.x and current.y == ngoal.y:
+ if current.x == goal_node.x and current.y == goal_node.y:
print("Find goal")
- ngoal.pind = current.pind
- ngoal.cost = current.cost
+ goal_node.parent_index = current.parent_index
+ goal_node.cost = current.cost
break
# Remove the item from the open set
@@ -89,114 +106,113 @@ def planning(self, sx, sy, gx, gy):
# Add it to the closed set
closed_set[c_id] = current
- # expand search grid based on motion model
+ # expand_grid search grid based on motion model
for i, _ in enumerate(self.motion):
node = self.Node(current.x + self.motion[i][0],
current.y + self.motion[i][1],
current.cost + self.motion[i][2], c_id)
n_id = self.calc_grid_index(node)
- # If the node is in closed_set, do nothing
- if n_id in closed_set:
- continue
-
# If the node is not safe, do nothing
if not self.verify_node(node):
continue
+ if n_id in closed_set:
+ continue
+
if n_id not in open_set:
open_set[n_id] = node # discovered a new node
else:
- if open_set[n_id].cost >= node.cost:
+ if open_set[n_id].cost > node.cost:
# This path is the best until now. record it
open_set[n_id] = node
- rx, ry = self.calc_final_path(ngoal, closed_set)
+ rx, ry = self.calc_final_path(goal_node, closed_set)
return rx, ry
- def calc_final_path(self, ngoal, closedset):
+ def calc_final_path(self, goal_node, closed_set):
# generate final course
- rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [
- self.calc_grid_position(ngoal.y, self.miny)]
- pind = ngoal.pind
- while pind != -1:
- n = closedset[pind]
- rx.append(self.calc_grid_position(n.x, self.minx))
- ry.append(self.calc_grid_position(n.y, self.miny))
- pind = n.pind
+ rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [
+ self.calc_grid_position(goal_node.y, self.min_y)]
+ parent_index = goal_node.parent_index
+ while parent_index != -1:
+ n = closed_set[parent_index]
+ rx.append(self.calc_grid_position(n.x, self.min_x))
+ ry.append(self.calc_grid_position(n.y, self.min_y))
+ parent_index = n.parent_index
return rx, ry
@staticmethod
def calc_heuristic(n1, n2):
w = 1.0 # weight of heuristic
- d = w * math.sqrt((n1.x - n2.x) ** 2 + (n1.y - n2.y) ** 2)
+ d = w * math.hypot(n1.x - n2.x, n1.y - n2.y)
return d
- def calc_grid_position(self, index, minp):
+ def calc_grid_position(self, index, min_position):
"""
calc grid position
:param index:
- :param minp:
+ :param min_position:
:return:
"""
- pos = index * self.reso + minp
+ pos = index * self.resolution + min_position
return pos
- def calc_xyindex(self, position, min_pos):
- return round((position - min_pos) / self.reso)
+ def calc_xy_index(self, position, min_pos):
+ return round((position - min_pos) / self.resolution)
def calc_grid_index(self, node):
- return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
+ return (node.y - self.min_y) * self.x_width + (node.x - self.min_x)
def verify_node(self, node):
- px = self.calc_grid_position(node.x, self.minx)
- py = self.calc_grid_position(node.y, self.miny)
+ px = self.calc_grid_position(node.x, self.min_x)
+ py = self.calc_grid_position(node.y, self.min_y)
- if px < self.minx:
+ if px < self.min_x:
return False
- elif py < self.miny:
+ elif py < self.min_y:
return False
- elif px >= self.maxx:
+ elif px >= self.max_x:
return False
- elif py >= self.maxy:
+ elif py >= self.max_y:
return False
# collision check
- if self.obmap[node.x][node.y]:
+ if self.obstacle_map[node.x][node.y]:
return False
return True
def calc_obstacle_map(self, ox, oy):
- self.minx = round(min(ox))
- self.miny = round(min(oy))
- self.maxx = round(max(ox))
- self.maxy = round(max(oy))
- print("minx:", self.minx)
- print("miny:", self.miny)
- print("maxx:", self.maxx)
- print("maxy:", self.maxy)
+ self.min_x = round(min(ox))
+ self.min_y = round(min(oy))
+ self.max_x = round(max(ox))
+ self.max_y = round(max(oy))
+ print("min_x:", self.min_x)
+ print("min_y:", self.min_y)
+ print("max_x:", self.max_x)
+ print("max_y:", self.max_y)
- self.xwidth = round((self.maxx - self.minx) / self.reso)
- self.ywidth = round((self.maxy - self.miny) / self.reso)
- print("xwidth:", self.xwidth)
- print("ywidth:", self.ywidth)
+ self.x_width = round((self.max_x - self.min_x) / self.resolution)
+ self.y_width = round((self.max_y - self.min_y) / self.resolution)
+ print("x_width:", self.x_width)
+ print("y_width:", self.y_width)
# obstacle map generation
- self.obmap = [[False for i in range(self.ywidth)]
- for i in range(self.xwidth)]
- for ix in range(self.xwidth):
- x = self.calc_grid_position(ix, self.minx)
- for iy in range(self.ywidth):
- y = self.calc_grid_position(iy, self.miny)
+ self.obstacle_map = [[False for _ in range(self.y_width)]
+ for _ in range(self.x_width)]
+ for ix in range(self.x_width):
+ x = self.calc_grid_position(ix, self.min_x)
+ for iy in range(self.y_width):
+ y = self.calc_grid_position(iy, self.min_y)
for iox, ioy in zip(ox, oy):
- d = math.sqrt((iox - x) ** 2 + (ioy - y) ** 2)
+ d = math.hypot(iox - x, ioy - y)
if d <= self.rr:
- self.obmap[ix][iy] = True
+ self.obstacle_map[ix][iy] = True
break
@staticmethod
@@ -225,7 +241,7 @@ def main():
grid_size = 2.0 # [m]
robot_radius = 1.0 # [m]
- # set obstable positions
+ # set obstacle positions
ox, oy = [], []
for i in range(-10, 60):
ox.append(i)
@@ -258,6 +274,7 @@ def main():
if show_animation: # pragma: no cover
plt.plot(rx, ry, "-r")
+ plt.pause(0.001)
plt.show()
diff --git a/PathPlanning/AStar/a_star_searching_from_two_side.py b/PathPlanning/AStar/a_star_searching_from_two_side.py
new file mode 100644
index 0000000000..f43cea71b4
--- /dev/null
+++ b/PathPlanning/AStar/a_star_searching_from_two_side.py
@@ -0,0 +1,369 @@
+"""
+A* algorithm
+Author: Weicent
+randomly generate obstacles, start and goal point
+searching path from start and end simultaneously
+"""
+
+import numpy as np
+import matplotlib.pyplot as plt
+import math
+
+show_animation = True
+
+
+class Node:
+ """node with properties of g, h, coordinate and parent node"""
+
+ def __init__(self, G=0, H=0, coordinate=None, parent=None):
+ self.G = G
+ self.H = H
+ self.F = G + H
+ self.parent = parent
+ self.coordinate = coordinate
+
+ def reset_f(self):
+ self.F = self.G + self.H
+
+
+def hcost(node_coordinate, goal):
+ dx = abs(node_coordinate[0] - goal[0])
+ dy = abs(node_coordinate[1] - goal[1])
+ hcost = dx + dy
+ return hcost
+
+
+def gcost(fixed_node, update_node_coordinate):
+ dx = abs(fixed_node.coordinate[0] - update_node_coordinate[0])
+ dy = abs(fixed_node.coordinate[1] - update_node_coordinate[1])
+ gc = math.hypot(dx, dy) # gc = move from fixed_node to update_node
+ gcost = fixed_node.G + gc # gcost = move from start point to update_node
+ return gcost
+
+
+def boundary_and_obstacles(start, goal, top_vertex, bottom_vertex, obs_number):
+ """
+ :param start: start coordinate
+ :param goal: goal coordinate
+ :param top_vertex: top right vertex coordinate of boundary
+ :param bottom_vertex: bottom left vertex coordinate of boundary
+ :param obs_number: number of obstacles generated in the map
+ :return: boundary_obstacle array, obstacle list
+ """
+ # below can be merged into a rectangle boundary
+ ay = list(range(bottom_vertex[1], top_vertex[1]))
+ ax = [bottom_vertex[0]] * len(ay)
+ cy = ay
+ cx = [top_vertex[0]] * len(cy)
+ bx = list(range(bottom_vertex[0] + 1, top_vertex[0]))
+ by = [bottom_vertex[1]] * len(bx)
+ dx = [bottom_vertex[0]] + bx + [top_vertex[0]]
+ dy = [top_vertex[1]] * len(dx)
+
+ # generate random obstacles
+ ob_x = np.random.randint(bottom_vertex[0] + 1,
+ top_vertex[0], obs_number).tolist()
+ ob_y = np.random.randint(bottom_vertex[1] + 1,
+ top_vertex[1], obs_number).tolist()
+ # x y coordinate in certain order for boundary
+ x = ax + bx + cx + dx
+ y = ay + by + cy + dy
+ obstacle = np.vstack((ob_x, ob_y)).T.tolist()
+ # remove start and goal coordinate in obstacle list
+ obstacle = [coor for coor in obstacle if coor != start and coor != goal]
+ obs_array = np.array(obstacle)
+ bound = np.vstack((x, y)).T
+ bound_obs = np.vstack((bound, obs_array))
+ return bound_obs, obstacle
+
+
+def find_neighbor(node, ob, closed):
+ # Convert obstacles to a set for faster lookup
+ ob_set = set(map(tuple, ob.tolist()))
+ neighbor_set = set()
+
+ # Generate neighbors within the 3x3 grid around the node
+ for x in range(node.coordinate[0] - 1, node.coordinate[0] + 2):
+ for y in range(node.coordinate[1] - 1, node.coordinate[1] + 2):
+ coord = (x, y)
+ if coord not in ob_set and coord != tuple(node.coordinate):
+ neighbor_set.add(coord)
+
+ # Define neighbors in cardinal and diagonal directions
+ top_nei = (node.coordinate[0], node.coordinate[1] + 1)
+ bottom_nei = (node.coordinate[0], node.coordinate[1] - 1)
+ left_nei = (node.coordinate[0] - 1, node.coordinate[1])
+ right_nei = (node.coordinate[0] + 1, node.coordinate[1])
+ lt_nei = (node.coordinate[0] - 1, node.coordinate[1] + 1)
+ rt_nei = (node.coordinate[0] + 1, node.coordinate[1] + 1)
+ lb_nei = (node.coordinate[0] - 1, node.coordinate[1] - 1)
+ rb_nei = (node.coordinate[0] + 1, node.coordinate[1] - 1)
+
+ # Remove neighbors that violate diagonal motion rules
+ if top_nei in ob_set and left_nei in ob_set:
+ neighbor_set.discard(lt_nei)
+ if top_nei in ob_set and right_nei in ob_set:
+ neighbor_set.discard(rt_nei)
+ if bottom_nei in ob_set and left_nei in ob_set:
+ neighbor_set.discard(lb_nei)
+ if bottom_nei in ob_set and right_nei in ob_set:
+ neighbor_set.discard(rb_nei)
+
+ # Filter out neighbors that are in the closed set
+ closed_set = set(map(tuple, closed))
+ neighbor_set -= closed_set
+
+ return list(neighbor_set)
+
+
+
+def find_node_index(coordinate, node_list):
+ # find node index in the node list via its coordinate
+ ind = 0
+ for node in node_list:
+ if node.coordinate == coordinate:
+ target_node = node
+ ind = node_list.index(target_node)
+ break
+ return ind
+
+
+def find_path(open_list, closed_list, goal, obstacle):
+ # searching for the path, update open and closed list
+ # obstacle = obstacle and boundary
+ flag = len(open_list)
+ for i in range(flag):
+ node = open_list[0]
+ open_coordinate_list = [node.coordinate for node in open_list]
+ closed_coordinate_list = [node.coordinate for node in closed_list]
+ temp = find_neighbor(node, obstacle, closed_coordinate_list)
+ for element in temp:
+ if element in closed_list:
+ continue
+ elif element in open_coordinate_list:
+ # if node in open list, update g value
+ ind = open_coordinate_list.index(element)
+ new_g = gcost(node, element)
+ if new_g <= open_list[ind].G:
+ open_list[ind].G = new_g
+ open_list[ind].reset_f()
+ open_list[ind].parent = node
+ else: # new coordinate, create corresponding node
+ ele_node = Node(coordinate=element, parent=node,
+ G=gcost(node, element), H=hcost(element, goal))
+ open_list.append(ele_node)
+ open_list.remove(node)
+ closed_list.append(node)
+ open_list.sort(key=lambda x: x.F)
+ return open_list, closed_list
+
+
+def node_to_coordinate(node_list):
+ # convert node list into coordinate list and array
+ coordinate_list = [node.coordinate for node in node_list]
+ return coordinate_list
+
+
+def check_node_coincide(close_ls1, closed_ls2):
+ """
+ :param close_ls1: node closed list for searching from start
+ :param closed_ls2: node closed list for searching from end
+ :return: intersect node list for above two
+ """
+ # check if node in close_ls1 intersect with node in closed_ls2
+ cl1 = node_to_coordinate(close_ls1)
+ cl2 = node_to_coordinate(closed_ls2)
+ intersect_ls = [node for node in cl1 if node in cl2]
+ return intersect_ls
+
+
+def find_surrounding(coordinate, obstacle):
+ # find obstacles around node, help to draw the borderline
+ boundary: list = []
+ for x in range(coordinate[0] - 1, coordinate[0] + 2):
+ for y in range(coordinate[1] - 1, coordinate[1] + 2):
+ if [x, y] in obstacle:
+ boundary.append([x, y])
+ return boundary
+
+
+def get_border_line(node_closed_ls, obstacle):
+ # if no path, find border line which confine goal or robot
+ border: list = []
+ coordinate_closed_ls = node_to_coordinate(node_closed_ls)
+ for coordinate in coordinate_closed_ls:
+ temp = find_surrounding(coordinate, obstacle)
+ border = border + temp
+ border_ary = np.array(border)
+ return border_ary
+
+
+def get_path(org_list, goal_list, coordinate):
+ # get path from start to end
+ path_org: list = []
+ path_goal: list = []
+ ind = find_node_index(coordinate, org_list)
+ node = org_list[ind]
+ while node != org_list[0]:
+ path_org.append(node.coordinate)
+ node = node.parent
+ path_org.append(org_list[0].coordinate)
+ ind = find_node_index(coordinate, goal_list)
+ node = goal_list[ind]
+ while node != goal_list[0]:
+ path_goal.append(node.coordinate)
+ node = node.parent
+ path_goal.append(goal_list[0].coordinate)
+ path_org.reverse()
+ path = path_org + path_goal
+ path = np.array(path)
+ return path
+
+
+def random_coordinate(bottom_vertex, top_vertex):
+ # generate random coordinates inside maze
+ coordinate = [np.random.randint(bottom_vertex[0] + 1, top_vertex[0]),
+ np.random.randint(bottom_vertex[1] + 1, top_vertex[1])]
+ return coordinate
+
+
+def draw(close_origin, close_goal, start, end, bound):
+ # plot the map
+ if not close_goal.tolist(): # ensure the close_goal not empty
+ # in case of the obstacle number is really large (>4500), the
+ # origin is very likely blocked at the first search, and then
+ # the program is over and the searching from goal to origin
+ # will not start, which remain the closed_list for goal == []
+ # in order to plot the map, add the end coordinate to array
+ close_goal = np.array([end])
+ plt.cla()
+ plt.gcf().set_size_inches(11, 9, forward=True)
+ plt.axis('equal')
+ plt.plot(close_origin[:, 0], close_origin[:, 1], 'oy')
+ plt.plot(close_goal[:, 0], close_goal[:, 1], 'og')
+ plt.plot(bound[:, 0], bound[:, 1], 'sk')
+ plt.plot(end[0], end[1], '*b', label='Goal')
+ plt.plot(start[0], start[1], '^b', label='Origin')
+ plt.legend()
+ plt.pause(0.0001)
+
+
+def draw_control(org_closed, goal_closed, flag, start, end, bound, obstacle):
+ """
+ control the plot process, evaluate if the searching finished
+ flag == 0 : draw the searching process and plot path
+ flag == 1 or 2 : start or end is blocked, draw the border line
+ """
+ stop_loop = 0 # stop sign for the searching
+ org_closed_ls = node_to_coordinate(org_closed)
+ org_array = np.array(org_closed_ls)
+ goal_closed_ls = node_to_coordinate(goal_closed)
+ goal_array = np.array(goal_closed_ls)
+ path = None
+ if show_animation: # draw the searching process
+ draw(org_array, goal_array, start, end, bound)
+ if flag == 0:
+ node_intersect = check_node_coincide(org_closed, goal_closed)
+ if node_intersect: # a path is find
+ path = get_path(org_closed, goal_closed, node_intersect[0])
+ stop_loop = 1
+ print('Path found!')
+ if show_animation: # draw the path
+ plt.plot(path[:, 0], path[:, 1], '-r')
+ plt.title('Robot Arrived', size=20, loc='center')
+ plt.pause(0.01)
+ plt.show()
+ elif flag == 1: # start point blocked first
+ stop_loop = 1
+ print('There is no path to the goal! Start point is blocked!')
+ elif flag == 2: # end point blocked first
+ stop_loop = 1
+ print('There is no path to the goal! End point is blocked!')
+ if show_animation: # blocked case, draw the border line
+ info = 'There is no path to the goal!' \
+ ' Robot&Goal are split by border' \
+ ' shown in red \'x\'!'
+ if flag == 1:
+ border = get_border_line(org_closed, obstacle)
+ plt.plot(border[:, 0], border[:, 1], 'xr')
+ plt.title(info, size=14, loc='center')
+ plt.pause(0.01)
+ plt.show()
+ elif flag == 2:
+ border = get_border_line(goal_closed, obstacle)
+ plt.plot(border[:, 0], border[:, 1], 'xr')
+ plt.title(info, size=14, loc='center')
+ plt.pause(0.01)
+ plt.show()
+ return stop_loop, path
+
+
+def searching_control(start, end, bound, obstacle):
+ """manage the searching process, start searching from two side"""
+ # initial origin node and end node
+ origin = Node(coordinate=start, H=hcost(start, end))
+ goal = Node(coordinate=end, H=hcost(end, start))
+ # list for searching from origin to goal
+ origin_open: list = [origin]
+ origin_close: list = []
+ # list for searching from goal to origin
+ goal_open = [goal]
+ goal_close: list = []
+ # initial target
+ target_goal = end
+ # flag = 0 (not blocked) 1 (start point blocked) 2 (end point blocked)
+ flag = 0 # init flag
+ path = None
+ while True:
+ # searching from start to end
+ origin_open, origin_close = \
+ find_path(origin_open, origin_close, target_goal, bound)
+ if not origin_open: # no path condition
+ flag = 1 # origin node is blocked
+ draw_control(origin_close, goal_close, flag, start, end, bound,
+ obstacle)
+ break
+ # update target for searching from end to start
+ target_origin = min(origin_open, key=lambda x: x.F).coordinate
+
+ # searching from end to start
+ goal_open, goal_close = \
+ find_path(goal_open, goal_close, target_origin, bound)
+ if not goal_open: # no path condition
+ flag = 2 # goal is blocked
+ draw_control(origin_close, goal_close, flag, start, end, bound,
+ obstacle)
+ break
+ # update target for searching from start to end
+ target_goal = min(goal_open, key=lambda x: x.F).coordinate
+
+ # continue searching, draw the process
+ stop_sign, path = draw_control(origin_close, goal_close, flag, start,
+ end, bound, obstacle)
+ if stop_sign:
+ break
+ return path
+
+
+def main(obstacle_number=1500):
+ print(__file__ + ' start!')
+
+ top_vertex = [60, 60] # top right vertex of boundary
+ bottom_vertex = [0, 0] # bottom left vertex of boundary
+
+ # generate start and goal point randomly
+ start = random_coordinate(bottom_vertex, top_vertex)
+ end = random_coordinate(bottom_vertex, top_vertex)
+
+ # generate boundary and obstacles
+ bound, obstacle = boundary_and_obstacles(start, end, top_vertex,
+ bottom_vertex,
+ obstacle_number)
+
+ path = searching_control(start, end, bound, obstacle)
+ if not show_animation:
+ print(path)
+
+
+if __name__ == '__main__':
+ main(obstacle_number=1500)
diff --git a/PathPlanning/AStar/a_star_variants.py b/PathPlanning/AStar/a_star_variants.py
new file mode 100644
index 0000000000..e0053ee224
--- /dev/null
+++ b/PathPlanning/AStar/a_star_variants.py
@@ -0,0 +1,483 @@
+"""
+a star variants
+author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it)
+Source: http://theory.stanford.edu/~amitp/GameProgramming/Variations.html
+"""
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+show_animation = True
+use_beam_search = False
+use_iterative_deepening = False
+use_dynamic_weighting = False
+use_theta_star = False
+use_jump_point = False
+
+beam_capacity = 30
+max_theta = 5
+only_corners = False
+max_corner = 5
+w, epsilon, upper_bound_depth = 1, 4, 500
+
+
+def draw_horizontal_line(start_x, start_y, length, o_x, o_y, o_dict):
+ for i in range(start_x, start_x + length):
+ for j in range(start_y, start_y + 2):
+ o_x.append(i)
+ o_y.append(j)
+ o_dict[(i, j)] = True
+
+
+def draw_vertical_line(start_x, start_y, length, o_x, o_y, o_dict):
+ for i in range(start_x, start_x + 2):
+ for j in range(start_y, start_y + length):
+ o_x.append(i)
+ o_y.append(j)
+ o_dict[(i, j)] = True
+
+
+def in_line_of_sight(obs_grid, x1, y1, x2, y2):
+ t = 0
+ while t <= 0.5:
+ xt = (1 - t) * x1 + t * x2
+ yt = (1 - t) * y1 + t * y2
+ if obs_grid[(int(xt), int(yt))]:
+ return False, None
+ xt = (1 - t) * x2 + t * x1
+ yt = (1 - t) * y2 + t * y1
+ if obs_grid[(int(xt), int(yt))]:
+ return False, None
+ t += 0.001
+ dist = np.linalg.norm(np.array([x1, y1] - np.array([x2, y2])))
+ return True, dist
+
+
+def key_points(o_dict):
+ offsets1 = [(1, 0), (0, 1), (-1, 0), (1, 0)]
+ offsets2 = [(1, 1), (-1, 1), (-1, -1), (1, -1)]
+ offsets3 = [(0, 1), (-1, 0), (0, -1), (0, -1)]
+ c_list = []
+ for grid_point, obs_status in o_dict.items():
+ if obs_status:
+ continue
+ empty_space = True
+ x, y = grid_point
+ for i in [-1, 0, 1]:
+ for j in [-1, 0, 1]:
+ if (x + i, y + j) not in o_dict.keys():
+ continue
+ if o_dict[(x + i, y + j)]:
+ empty_space = False
+ break
+ if empty_space:
+ continue
+ for offset1, offset2, offset3 in zip(offsets1, offsets2, offsets3):
+ i1, j1 = offset1
+ i2, j2 = offset2
+ i3, j3 = offset3
+ if ((x + i1, y + j1) not in o_dict.keys()) or \
+ ((x + i2, y + j2) not in o_dict.keys()) or \
+ ((x + i3, y + j3) not in o_dict.keys()):
+ continue
+ obs_count = 0
+ if o_dict[(x + i1, y + j1)]:
+ obs_count += 1
+ if o_dict[(x + i2, y + j2)]:
+ obs_count += 1
+ if o_dict[(x + i3, y + j3)]:
+ obs_count += 1
+ if obs_count == 3 or obs_count == 1:
+ c_list.append((x, y))
+ if show_animation:
+ plt.plot(x, y, ".y")
+ break
+ if only_corners:
+ return c_list
+
+ e_list = []
+ for corner in c_list:
+ x1, y1 = corner
+ for other_corner in c_list:
+ x2, y2 = other_corner
+ if x1 == x2 and y1 == y2:
+ continue
+ reachable, _ = in_line_of_sight(o_dict, x1, y1, x2, y2)
+ if not reachable:
+ continue
+ x_m, y_m = int((x1 + x2) / 2), int((y1 + y2) / 2)
+ e_list.append((x_m, y_m))
+ if show_animation:
+ plt.plot(x_m, y_m, ".y")
+ return c_list + e_list
+
+
+class SearchAlgo:
+ def __init__(self, obs_grid, goal_x, goal_y, start_x, start_y,
+ limit_x, limit_y, corner_list=None):
+ self.start_pt = [start_x, start_y]
+ self.goal_pt = [goal_x, goal_y]
+ self.obs_grid = obs_grid
+ g_cost, h_cost = 0, self.get_hval(start_x, start_y, goal_x, goal_y)
+ f_cost = g_cost + h_cost
+ self.all_nodes, self.open_set = {}, []
+
+ if use_jump_point:
+ for corner in corner_list:
+ i, j = corner
+ h_c = self.get_hval(i, j, goal_x, goal_y)
+ self.all_nodes[(i, j)] = {'pos': [i, j], 'pred': None,
+ 'gcost': np.inf, 'hcost': h_c,
+ 'fcost': np.inf,
+ 'open': True, 'in_open_list': False}
+ self.all_nodes[tuple(self.goal_pt)] = \
+ {'pos': self.goal_pt, 'pred': None,
+ 'gcost': np.inf, 'hcost': 0, 'fcost': np.inf,
+ 'open': True, 'in_open_list': True}
+ else:
+ for i in range(limit_x):
+ for j in range(limit_y):
+ h_c = self.get_hval(i, j, goal_x, goal_y)
+ self.all_nodes[(i, j)] = {'pos': [i, j], 'pred': None,
+ 'gcost': np.inf, 'hcost': h_c,
+ 'fcost': np.inf,
+ 'open': True,
+ 'in_open_list': False}
+ self.all_nodes[tuple(self.start_pt)] = \
+ {'pos': self.start_pt, 'pred': None,
+ 'gcost': g_cost, 'hcost': h_cost, 'fcost': f_cost,
+ 'open': True, 'in_open_list': True}
+ self.open_set.append(self.all_nodes[tuple(self.start_pt)])
+
+ @staticmethod
+ def get_hval(x1, y1, x2, y2):
+ x, y = x1, y1
+ val = 0
+ while x != x2 or y != y2:
+ if x != x2 and y != y2:
+ val += 14
+ else:
+ val += 10
+ x, y = x + np.sign(x2 - x), y + np.sign(y2 - y)
+ return val
+
+ def get_farthest_point(self, x, y, i, j):
+ i_temp, j_temp = i, j
+ counter = 1
+ got_goal = False
+ while not self.obs_grid[(x + i_temp, y + j_temp)] and \
+ counter < max_theta:
+ i_temp += i
+ j_temp += j
+ counter += 1
+ if [x + i_temp, y + j_temp] == self.goal_pt:
+ got_goal = True
+ break
+ if (x + i_temp, y + j_temp) not in self.obs_grid.keys():
+ break
+ return i_temp - 2*i, j_temp - 2*j, counter, got_goal
+
+ def jump_point(self):
+ """Jump point: Instead of exploring all empty spaces of the
+ map, just explore the corners."""
+
+ goal_found = False
+ while len(self.open_set) > 0:
+ self.open_set = sorted(self.open_set, key=lambda x: x['fcost'])
+ lowest_f = self.open_set[0]['fcost']
+ lowest_h = self.open_set[0]['hcost']
+ lowest_g = self.open_set[0]['gcost']
+ p = 0
+ for p_n in self.open_set[1:]:
+ if p_n['fcost'] == lowest_f and \
+ p_n['gcost'] < lowest_g:
+ lowest_g = p_n['gcost']
+ p += 1
+ elif p_n['fcost'] == lowest_f and \
+ p_n['gcost'] == lowest_g and \
+ p_n['hcost'] < lowest_h:
+ lowest_h = p_n['hcost']
+ p += 1
+ else:
+ break
+ current_node = self.all_nodes[tuple(self.open_set[p]['pos'])]
+ x1, y1 = current_node['pos']
+
+ for cand_pt, cand_node in self.all_nodes.items():
+ x2, y2 = cand_pt
+ if x1 == x2 and y1 == y2:
+ continue
+ if np.linalg.norm(np.array([x1, y1] -
+ np.array([x2, y2]))) > max_corner:
+ continue
+ reachable, offset = in_line_of_sight(self.obs_grid, x1,
+ y1, x2, y2)
+ if not reachable:
+ continue
+
+ if list(cand_pt) == self.goal_pt:
+ current_node['open'] = False
+ self.all_nodes[tuple(cand_pt)]['pred'] = \
+ current_node['pos']
+ goal_found = True
+ break
+
+ g_cost = offset + current_node['gcost']
+ h_cost = self.all_nodes[cand_pt]['hcost']
+ f_cost = g_cost + h_cost
+ cand_pt = tuple(cand_pt)
+ if f_cost < self.all_nodes[cand_pt]['fcost']:
+ self.all_nodes[cand_pt]['pred'] = current_node['pos']
+ self.all_nodes[cand_pt]['gcost'] = g_cost
+ self.all_nodes[cand_pt]['fcost'] = f_cost
+ if not self.all_nodes[cand_pt]['in_open_list']:
+ self.open_set.append(self.all_nodes[cand_pt])
+ self.all_nodes[cand_pt]['in_open_list'] = True
+ if show_animation:
+ plt.plot(cand_pt[0], cand_pt[1], "r*")
+
+ if goal_found:
+ break
+ if show_animation:
+ plt.pause(0.001)
+ if goal_found:
+ current_node = self.all_nodes[tuple(self.goal_pt)]
+ while goal_found:
+ if current_node['pred'] is None:
+ break
+ x = [current_node['pos'][0], current_node['pred'][0]]
+ y = [current_node['pos'][1], current_node['pred'][1]]
+ current_node = self.all_nodes[tuple(current_node['pred'])]
+ if show_animation:
+ plt.plot(x, y, "b")
+ plt.pause(0.001)
+ if goal_found:
+ break
+
+ current_node['open'] = False
+ current_node['in_open_list'] = False
+ if show_animation:
+ plt.plot(current_node['pos'][0], current_node['pos'][1], "g*")
+ del self.open_set[p]
+ current_node['fcost'], current_node['hcost'] = np.inf, np.inf
+ if show_animation:
+ plt.title('Jump Point')
+ plt.show()
+
+ def a_star(self):
+ """Beam search: Maintain an open list of just 30 nodes.
+ If more than 30 nodes, then get rid of nodes with high
+ f values.
+ Iterative deepening: At every iteration, get a cut-off
+ value for the f cost. This cut-off is minimum of the f
+ value of all nodes whose f value is higher than the
+ current cut-off value. Nodes with f value higher than
+ the current cut off value are not put in the open set.
+ Dynamic weighting: Multiply heuristic with the following:
+ (1 + epsilon - (epsilon*d)/N) where d is the current
+ iteration of loop and N is upper bound on number of
+ iterations.
+ Theta star: Same as A star but you don't need to move
+ one neighbor at a time. In fact, you can look for the
+ next node as far out as you can as long as there is a
+ clear line of sight from your current node to that node."""
+ if show_animation:
+ if use_beam_search:
+ plt.title('A* with beam search')
+ elif use_iterative_deepening:
+ plt.title('A* with iterative deepening')
+ elif use_dynamic_weighting:
+ plt.title('A* with dynamic weighting')
+ elif use_theta_star:
+ plt.title('Theta*')
+ else:
+ plt.title('A*')
+
+ goal_found = False
+ curr_f_thresh = np.inf
+ depth = 0
+ no_valid_f = False
+ w = None
+ while len(self.open_set) > 0:
+ self.open_set = sorted(self.open_set, key=lambda x: x['fcost'])
+ lowest_f = self.open_set[0]['fcost']
+ lowest_h = self.open_set[0]['hcost']
+ lowest_g = self.open_set[0]['gcost']
+ p = 0
+ for p_n in self.open_set[1:]:
+ if p_n['fcost'] == lowest_f and \
+ p_n['gcost'] < lowest_g:
+ lowest_g = p_n['gcost']
+ p += 1
+ elif p_n['fcost'] == lowest_f and \
+ p_n['gcost'] == lowest_g and \
+ p_n['hcost'] < lowest_h:
+ lowest_h = p_n['hcost']
+ p += 1
+ else:
+ break
+ current_node = self.all_nodes[tuple(self.open_set[p]['pos'])]
+
+ while len(self.open_set) > beam_capacity and use_beam_search:
+ del self.open_set[-1]
+
+ f_cost_list = []
+ if use_dynamic_weighting:
+ w = (1 + epsilon - epsilon*depth/upper_bound_depth)
+ for i in range(-1, 2):
+ for j in range(-1, 2):
+ x, y = current_node['pos']
+ if (i == 0 and j == 0) or \
+ ((x + i, y + j) not in self.obs_grid.keys()):
+ continue
+ if (i, j) in [(1, 0), (0, 1), (-1, 0), (0, -1)]:
+ offset = 10
+ else:
+ offset = 14
+ if use_theta_star:
+ new_i, new_j, counter, goal_found = \
+ self.get_farthest_point(x, y, i, j)
+ offset = offset * counter
+ cand_pt = [current_node['pos'][0] + new_i,
+ current_node['pos'][1] + new_j]
+ else:
+ cand_pt = [current_node['pos'][0] + i,
+ current_node['pos'][1] + j]
+
+ if use_theta_star and goal_found:
+ current_node['open'] = False
+ cand_pt = self.goal_pt
+ self.all_nodes[tuple(cand_pt)]['pred'] = \
+ current_node['pos']
+ break
+
+ if cand_pt == self.goal_pt:
+ current_node['open'] = False
+ self.all_nodes[tuple(cand_pt)]['pred'] = \
+ current_node['pos']
+ goal_found = True
+ break
+
+ cand_pt = tuple(cand_pt)
+ no_valid_f = self.update_node_cost(cand_pt, curr_f_thresh,
+ current_node,
+ f_cost_list, no_valid_f,
+ offset, w)
+ if goal_found:
+ break
+ if show_animation:
+ plt.pause(0.001)
+ if goal_found:
+ current_node = self.all_nodes[tuple(self.goal_pt)]
+ while goal_found:
+ if current_node['pred'] is None:
+ break
+ if use_theta_star or use_jump_point:
+ x, y = [current_node['pos'][0], current_node['pred'][0]], \
+ [current_node['pos'][1], current_node['pred'][1]]
+ if show_animation:
+ plt.plot(x, y, "b")
+ else:
+ if show_animation:
+ plt.plot(current_node['pred'][0],
+ current_node['pred'][1], "b*")
+ current_node = self.all_nodes[tuple(current_node['pred'])]
+ if goal_found:
+ break
+
+ if use_iterative_deepening and f_cost_list:
+ curr_f_thresh = min(f_cost_list)
+ if use_iterative_deepening and not f_cost_list:
+ curr_f_thresh = np.inf
+ if use_iterative_deepening and not f_cost_list and no_valid_f:
+ current_node['fcost'], current_node['hcost'] = np.inf, np.inf
+ continue
+
+ current_node['open'] = False
+ current_node['in_open_list'] = False
+ if show_animation:
+ plt.plot(current_node['pos'][0], current_node['pos'][1], "g*")
+ del self.open_set[p]
+ current_node['fcost'], current_node['hcost'] = np.inf, np.inf
+ depth += 1
+ if show_animation:
+ plt.show()
+
+ def update_node_cost(self, cand_pt, curr_f_thresh, current_node,
+ f_cost_list, no_valid_f, offset, w):
+ if not self.obs_grid[tuple(cand_pt)] and \
+ self.all_nodes[cand_pt]['open']:
+ g_cost = offset + current_node['gcost']
+ h_cost = self.all_nodes[cand_pt]['hcost']
+ if use_dynamic_weighting:
+ h_cost = h_cost * w
+ f_cost = g_cost + h_cost
+ if f_cost < self.all_nodes[cand_pt]['fcost'] and \
+ f_cost <= curr_f_thresh:
+ f_cost_list.append(f_cost)
+ self.all_nodes[cand_pt]['pred'] = \
+ current_node['pos']
+ self.all_nodes[cand_pt]['gcost'] = g_cost
+ self.all_nodes[cand_pt]['fcost'] = f_cost
+ if not self.all_nodes[cand_pt]['in_open_list']:
+ self.open_set.append(self.all_nodes[cand_pt])
+ self.all_nodes[cand_pt]['in_open_list'] = True
+ if show_animation:
+ plt.plot(cand_pt[0], cand_pt[1], "r*")
+ if curr_f_thresh < f_cost < \
+ self.all_nodes[cand_pt]['fcost']:
+ no_valid_f = True
+ return no_valid_f
+
+
+def main():
+ # set obstacle positions
+ obs_dict = {}
+ for i in range(51):
+ for j in range(51):
+ obs_dict[(i, j)] = False
+ o_x, o_y = [], []
+
+ s_x = 5.0
+ s_y = 5.0
+ g_x = 35.0
+ g_y = 45.0
+
+ # draw outer border of maze
+ draw_vertical_line(0, 0, 50, o_x, o_y, obs_dict)
+ draw_vertical_line(48, 0, 50, o_x, o_y, obs_dict)
+ draw_horizontal_line(0, 0, 50, o_x, o_y, obs_dict)
+ draw_horizontal_line(0, 48, 50, o_x, o_y, obs_dict)
+
+ # draw inner walls
+ all_x = [10, 10, 10, 15, 20, 20, 30, 30, 35, 30, 40, 45]
+ all_y = [10, 30, 45, 20, 5, 40, 10, 40, 5, 40, 10, 25]
+ all_len = [10, 10, 5, 10, 10, 5, 20, 10, 25, 10, 35, 15]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_vertical_line(x, y, l, o_x, o_y, obs_dict)
+
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [35, 40, 15, 10, 45, 20, 10, 15, 25, 45, 10, 30, 10, 40]
+ all_y = [5, 10, 15, 20, 20, 25, 30, 35, 35, 35, 40, 40, 45, 45]
+ all_len = [10, 5, 10, 10, 5, 5, 10, 5, 10, 5, 10, 5, 5, 5]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_horizontal_line(x, y, l, o_x, o_y, obs_dict)
+
+ if show_animation:
+ plt.plot(o_x, o_y, ".k")
+ plt.plot(s_x, s_y, "og")
+ plt.plot(g_x, g_y, "xb")
+ plt.grid(True)
+
+ if use_jump_point:
+ keypoint_list = key_points(obs_dict)
+ search_obj = SearchAlgo(obs_dict, g_x, g_y, s_x, s_y, 101, 101,
+ keypoint_list)
+ search_obj.jump_point()
+ else:
+ search_obj = SearchAlgo(obs_dict, g_x, g_y, s_x, s_y, 101, 101)
+ search_obj.a_star()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/BSplinePath/Figure_1.png b/PathPlanning/BSplinePath/Figure_1.png
deleted file mode 100644
index 539854ac29..0000000000
Binary files a/PathPlanning/BSplinePath/Figure_1.png and /dev/null differ
diff --git a/PathPlanning/BSplinePath/bspline_path.py b/PathPlanning/BSplinePath/bspline_path.py
index 0c453ad436..a2a396efaa 100644
--- a/PathPlanning/BSplinePath/bspline_path.py
+++ b/PathPlanning/BSplinePath/bspline_path.py
@@ -1,51 +1,147 @@
"""
-Path Plannting with B-Spline
+Path Planner with B-Spline
author: Atsushi Sakai (@Atsushi_twi)
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import numpy as np
import matplotlib.pyplot as plt
-import scipy.interpolate as si
-
-# parameter
-N = 3 # B Spline order
-
-
-def bspline_planning(x, y, sn):
- t = range(len(x))
- x_tup = si.splrep(t, x, k=N)
- y_tup = si.splrep(t, y, k=N)
-
- x_list = list(x_tup)
- xl = x.tolist()
- x_list[1] = xl + [0.0, 0.0, 0.0, 0.0]
-
- y_list = list(y_tup)
- yl = y.tolist()
- y_list[1] = yl + [0.0, 0.0, 0.0, 0.0]
-
- ipl_t = np.linspace(0.0, len(x) - 1, sn)
- rx = si.splev(ipl_t, x_list)
- ry = si.splev(ipl_t, y_list)
-
- return rx, ry
+import scipy.interpolate as interpolate
+
+from utils.plot import plot_curvature
+
+
+def approximate_b_spline_path(x: list,
+ y: list,
+ n_path_points: int,
+ degree: int = 3,
+ s=None,
+ ) -> tuple:
+ """
+ Approximate points with a B-Spline path
+
+ Parameters
+ ----------
+ x : array_like
+ x position list of approximated points
+ y : array_like
+ y position list of approximated points
+ n_path_points : int
+ number of path points
+ degree : int, optional
+ B Spline curve degree. Must be 2<= k <= 5. Default: 3.
+ s : int, optional
+ smoothing parameter. If this value is bigger, the path will be
+ smoother, but it will be less accurate. If this value is smaller,
+ the path will be more accurate, but it will be less smooth.
+ When `s` is 0, it is equivalent to the interpolation. Default is None,
+ in this case `s` will be `len(x)`.
+
+ Returns
+ -------
+ x : array
+ x positions of the result path
+ y : array
+ y positions of the result path
+ heading : array
+ heading of the result path
+ curvature : array
+ curvature of the result path
+
+ """
+ distances = _calc_distance_vector(x, y)
+
+ spl_i_x = interpolate.UnivariateSpline(distances, x, k=degree, s=s)
+ spl_i_y = interpolate.UnivariateSpline(distances, y, k=degree, s=s)
+
+ sampled = np.linspace(0.0, distances[-1], n_path_points)
+ return _evaluate_spline(sampled, spl_i_x, spl_i_y)
+
+
+def interpolate_b_spline_path(x, y,
+ n_path_points: int,
+ degree: int = 3) -> tuple:
+ """
+ Interpolate x-y points with a B-Spline path
+
+ Parameters
+ ----------
+ x : array_like
+ x positions of interpolated points
+ y : array_like
+ y positions of interpolated points
+ n_path_points : int
+ number of path points
+ degree : int, optional
+ B-Spline degree. Must be 2<= k <= 5. Default: 3
+
+ Returns
+ -------
+ x : array
+ x positions of the result path
+ y : array
+ y positions of the result path
+ heading : array
+ heading of the result path
+ curvature : array
+ curvature of the result path
+
+ """
+ return approximate_b_spline_path(x, y, n_path_points, degree, s=0.0)
+
+
+def _calc_distance_vector(x, y):
+ dx, dy = np.diff(x), np.diff(y)
+ distances = np.cumsum([np.hypot(idx, idy) for idx, idy in zip(dx, dy)])
+ distances = np.concatenate(([0.0], distances))
+ distances /= distances[-1]
+ return distances
+
+
+def _evaluate_spline(sampled, spl_i_x, spl_i_y):
+ x = spl_i_x(sampled)
+ y = spl_i_y(sampled)
+ dx = spl_i_x.derivative(1)(sampled)
+ dy = spl_i_y.derivative(1)(sampled)
+ heading = np.arctan2(dy, dx)
+ ddx = spl_i_x.derivative(2)(sampled)
+ ddy = spl_i_y.derivative(2)(sampled)
+ curvature = (ddy * dx - ddx * dy) / np.power(dx * dx + dy * dy, 2.0 / 3.0)
+ return np.array(x), y, heading, curvature,
def main():
print(__file__ + " start!!")
# way points
- x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0])
- y = np.array([0.0, -3.0, 1.0, 1.0, 3.0])
- sn = 100 # sampling number
+ way_point_x = [-1.0, 3.0, 4.0, 2.0, 1.0]
+ way_point_y = [0.0, -3.0, 1.0, 1.0, 3.0]
+ n_course_point = 50 # sampling number
+
+ plt.subplots()
+ rax, ray, heading, curvature = approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5)
+ plt.plot(rax, ray, '-r', label="Approximated B-Spline path")
+ plot_curvature(rax, ray, heading, curvature)
+
+ plt.title("B-Spline approximation")
+ plt.plot(way_point_x, way_point_y, '-og', label="way points")
+ plt.grid(True)
+ plt.legend()
+ plt.axis("equal")
- rx, ry = bspline_planning(x, y, sn)
+ plt.subplots()
+ rix, riy, heading, curvature = interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point)
+ plt.plot(rix, riy, '-b', label="Interpolated B-Spline path")
+ plot_curvature(rix, riy, heading, curvature)
- # show results
- plt.plot(x, y, '-og', label="Waypoints")
- plt.plot(rx, ry, '-r', label="B-Spline path")
+ plt.title("B-Spline interpolation")
+ plt.plot(way_point_x, way_point_y, '-og', label="way points")
plt.grid(True)
plt.legend()
plt.axis("equal")
diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrt_star.py
similarity index 59%
rename from PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py
rename to PathPlanning/BatchInformedRRTStar/batch_informed_rrt_star.py
index 366ec5acc2..92c3a58761 100644
--- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py
+++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrt_star.py
@@ -14,20 +14,28 @@
Reference: https://arxiv.org/abs/1405.5848
"""
-import random
-import numpy as np
import math
+import random
+
import matplotlib.pyplot as plt
+import numpy as np
show_animation = True
-class RTree(object):
+class RTree:
# Class to represent the explicit tree created
# while sampling through the state space
- def __init__(self, start=[0, 0], lowerLimit=[0, 0], upperLimit=[10, 10], resolution=1):
+ def __init__(self, start=None, lowerLimit=None, upperLimit=None,
+ resolution=1.0):
+ if upperLimit is None:
+ upperLimit = [10, 10]
+ if lowerLimit is None:
+ lowerLimit = [0, 0]
+ if start is None:
+ start = [0, 0]
self.vertices = dict()
self.edges = []
self.start = start
@@ -42,20 +50,21 @@ def __init__(self, start=[0, 0], lowerLimit=[0, 0], upperLimit=[10, 10], resolut
self.num_cells[idx] = np.ceil(
(upperLimit[idx] - lowerLimit[idx]) / resolution)
- vertex_id = self.realWorldToNodeId(start)
+ vertex_id = self.real_world_to_node_id(start)
self.vertices[vertex_id] = []
- def getRootId(self):
+ @staticmethod
+ def get_root_id():
# return the id of the root of the tree
return 0
- def addVertex(self, vertex):
+ def add_vertex(self, vertex):
# add a vertex to the tree
- vertex_id = self.realWorldToNodeId(vertex)
+ vertex_id = self.real_world_to_node_id(vertex)
self.vertices[vertex_id] = []
return vertex_id
- def addEdge(self, v, x):
+ def add_edge(self, v, x):
# create an edge between v and x vertices
if (v, x) not in self.edges:
self.edges.append((v, x))
@@ -63,7 +72,7 @@ def addEdge(self, v, x):
self.vertices[v].append(x)
self.vertices[x].append(v)
- def realCoordsToGridCoord(self, real_coord):
+ def real_coords_to_grid_coord(self, real_coord):
# convert real world coordinates to grid space
# depends on the resolution of the grid
# the output is the same as real world coords if the resolution
@@ -71,10 +80,10 @@ def realCoordsToGridCoord(self, real_coord):
coord = [0] * self.dimension
for i in range(len(coord)):
start = self.lowerLimit[i] # start of the grid space
- coord[i] = np.around((real_coord[i] - start) / self.resolution)
+ coord[i] = int(np.around((real_coord[i] - start) / self.resolution))
return coord
- def gridCoordinateToNodeId(self, coord):
+ def grid_coordinate_to_node_id(self, coord):
# This function maps a grid coordinate to a unique
# node id
nodeId = 0
@@ -85,13 +94,14 @@ def gridCoordinateToNodeId(self, coord):
nodeId = nodeId + coord[i] * product
return nodeId
- def realWorldToNodeId(self, real_coord):
+ def real_world_to_node_id(self, real_coord):
# first convert the given coordinates to grid space and then
# convert the grid space coordinates to a unique node id
- return self.gridCoordinateToNodeId(self.realCoordsToGridCoord(real_coord))
+ return self.grid_coordinate_to_node_id(
+ self.real_coords_to_grid_coord(real_coord))
- def gridCoordToRealWorldCoord(self, coord):
- # This function smaps a grid coordinate in discrete space
+ def grid_coord_to_real_world_coord(self, coord):
+ # This function maps a grid coordinate in discrete space
# to a configuration in the full configuration space
config = [0] * self.dimension
for i in range(0, len(coord)):
@@ -102,7 +112,7 @@ def gridCoordToRealWorldCoord(self, coord):
config[i] = start + grid_step
return config
- def nodeIdToGridCoord(self, node_id):
+ def node_id_to_grid_coord(self, node_id):
# This function maps a node id to the associated
# grid coordinate
coord = [0] * len(self.lowerLimit)
@@ -115,15 +125,14 @@ def nodeIdToGridCoord(self, node_id):
node_id = node_id - (coord[i] * prod)
return coord
- def nodeIdToRealWorldCoord(self, nid):
- # This function maps a node in discrete space to a configuraiton
+ def node_id_to_real_world_coord(self, nid):
+ # This function maps a node in discrete space to a configuration
# in the full configuration space
- return self.gridCoordToRealWorldCoord(self.nodeIdToGridCoord(nid))
-
-# Uses Batch Informed Trees to find a path from start to goal
+ return self.grid_coord_to_real_world_coord(
+ self.node_id_to_grid_coord(nid))
-class BITStar(object):
+class BITStar:
def __init__(self, start, goal,
obstacleList, randArea, eta=2.0,
@@ -131,10 +140,12 @@ def __init__(self, start, goal,
self.start = start
self.goal = goal
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.maxIter = maxIter
+ self.min_rand = randArea[0]
+ self.max_rand = randArea[1]
+ self.max_iIter = maxIter
self.obstacleList = obstacleList
+ self.startId = None
+ self.goalId = None
self.vertex_queue = []
self.edge_queue = []
@@ -154,8 +165,8 @@ def __init__(self, start, goal,
upperLimit=upperLimit, resolution=0.01)
def setup_planning(self):
- self.startId = self.tree.realWorldToNodeId(self.start)
- self.goalId = self.tree.realWorldToNodeId(self.goal)
+ self.startId = self.tree.real_world_to_node_id(self.start)
+ self.goalId = self.tree.real_world_to_node_id(self.goal)
# add goal to the samples
self.samples[self.goalId] = self.goal
@@ -163,33 +174,34 @@ def setup_planning(self):
self.f_scores[self.goalId] = 0
# add the start id to the tree
- self.tree.addVertex(self.start)
+ self.tree.add_vertex(self.start)
self.g_scores[self.startId] = 0
- self.f_scores[self.startId] = self.computeHeuristicCost(
+ self.f_scores[self.startId] = self.compute_heuristic_cost(
self.startId, self.goalId)
# max length we expect to find in our 'informed' sample space, starts as infinite
cBest = self.g_scores[self.goalId]
# Computing the sampling space
- cMin = math.sqrt(pow(self.start[0] - self.goal[0], 2)
- + pow(self.start[1] - self.goal[1], 2)) / 1.5
+ cMin = math.hypot(self.start[0] - self.goal[0],
+ self.start[1] - self.goal[1]) / 1.5
xCenter = np.array([[(self.start[0] + self.goal[0]) / 2.0],
[(self.start[1] + self.goal[1]) / 2.0], [0]])
a1 = np.array([[(self.goal[0] - self.start[0]) / cMin],
[(self.goal[1] - self.start[1]) / cMin], [0]])
- etheta = math.atan2(a1[1], a1[0])
- # first column of idenity matrix transposed
+ eTheta = math.atan2(a1[1, 0], a1[0, 0])
+ # first column of identity matrix transposed
id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3)
M = np.dot(a1, id1_t)
- U, S, Vh = np.linalg.svd(M, 1, 1)
+ U, S, Vh = np.linalg.svd(M, True, True)
C = np.dot(np.dot(U, np.diag(
- [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh)
+ [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])),
+ Vh)
- self.samples.update(self.informedSample(
+ self.samples.update(self.informed_sample(
200, cBest, cMin, xCenter, C))
- return etheta, cMin, xCenter, C, cBest
+ return eTheta, cMin, xCenter, C, cBest
def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest):
@@ -207,7 +219,7 @@ def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest):
else:
m = 100
cBest = self.g_scores[self.goalId]
- self.samples.update(self.informedSample(
+ self.samples.update(self.informed_sample(
m, cBest, cMin, xCenter, C))
# make the old vertices the new vertices
@@ -220,31 +232,37 @@ def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest):
def plan(self, animation=True):
- etheta, cMin, xCenter, C, cBest = self.setup_planning()
+ eTheta, cMin, xCenter, C, cBest = self.setup_planning()
iterations = 0
foundGoal = False
# run until done
- while (iterations < self.maxIter):
+ while iterations < self.max_iIter:
cBest = self.setup_sample(iterations,
foundGoal, cMin, xCenter, C, cBest)
# expand the best vertices until an edge is better than the vertex
# this is done because the vertex cost represents the lower bound
# on the edge cost
- while(self.bestVertexQueueValue() <= self.bestEdgeQueueValue()):
- self.expandVertex(self.bestInVertexQueue())
+ while self.best_vertex_queue_value() <= \
+ self.best_edge_queue_value():
+ self.expand_vertex(self.best_in_vertex_queue())
# add the best edge to the tree
- bestEdge = self.bestInEdgeQueue()
+ bestEdge = self.best_in_edge_queue()
self.edge_queue.remove(bestEdge)
# Check if this can improve the current solution
- estimatedCostOfVertex = self.g_scores[bestEdge[0]] + self.computeDistanceCost(
- bestEdge[0], bestEdge[1]) + self.computeHeuristicCost(bestEdge[1], self.goalId)
- estimatedCostOfEdge = self.computeDistanceCost(self.startId, bestEdge[0]) + self.computeHeuristicCost(
- bestEdge[0], bestEdge[1]) + self.computeHeuristicCost(bestEdge[1], self.goalId)
- actualCostOfEdge = self.g_scores[bestEdge[0]] + \
- self.computeDistanceCost(bestEdge[0], bestEdge[1])
+ estimatedCostOfVertex = self.g_scores[bestEdge[
+ 0]] + self.compute_distance_cost(
+ bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(
+ bestEdge[1], self.goalId)
+ estimatedCostOfEdge = self.compute_distance_cost(
+ self.startId, bestEdge[0]) + self.compute_heuristic_cost(
+ bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(
+ bestEdge[1], self.goalId)
+ actualCostOfEdge = self.g_scores[
+ bestEdge[0]] + self.compute_distance_cost(
+ bestEdge[0], bestEdge[1])
f1 = estimatedCostOfVertex < self.g_scores[self.goalId]
f2 = estimatedCostOfEdge < self.g_scores[self.goalId]
@@ -252,46 +270,50 @@ def plan(self, animation=True):
if f1 and f2 and f3:
# connect this edge
- firstCoord = self.tree.nodeIdToRealWorldCoord(
+ firstCoord = self.tree.node_id_to_real_world_coord(
bestEdge[0])
- secondCoord = self.tree.nodeIdToRealWorldCoord(
+ secondCoord = self.tree.node_id_to_real_world_coord(
bestEdge[1])
path = self.connect(firstCoord, secondCoord)
- lastEdge = self.tree.realWorldToNodeId(secondCoord)
+ lastEdge = self.tree.real_world_to_node_id(secondCoord)
if path is None or len(path) == 0:
continue
nextCoord = path[len(path) - 1, :]
- nextCoordPathId = self.tree.realWorldToNodeId(
+ nextCoordPathId = self.tree.real_world_to_node_id(
nextCoord)
bestEdge = (bestEdge[0], nextCoordPathId)
- if(bestEdge[1] in self.tree.vertices.keys()):
+ if bestEdge[1] in self.tree.vertices.keys():
continue
else:
try:
del self.samples[bestEdge[1]]
- except(KeyError):
+ except KeyError:
+ # invalid sample key
pass
- eid = self.tree.addVertex(nextCoord)
+ eid = self.tree.add_vertex(nextCoord)
self.vertex_queue.append(eid)
- if eid == self.goalId or bestEdge[0] == self.goalId or bestEdge[1] == self.goalId:
+ if eid == self.goalId or bestEdge[0] == self.goalId or \
+ bestEdge[1] == self.goalId:
print("Goal found")
foundGoal = True
- self.tree.addEdge(bestEdge[0], bestEdge[1])
+ self.tree.add_edge(bestEdge[0], bestEdge[1])
- g_score = self.computeDistanceCost(
+ g_score = self.compute_distance_cost(
bestEdge[0], bestEdge[1])
- self.g_scores[bestEdge[1]] = g_score + \
- self.g_scores[bestEdge[0]]
- self.f_scores[bestEdge[1]] = g_score + \
- self.computeHeuristicCost(bestEdge[1], self.goalId)
- self.updateGraph()
+ self.g_scores[bestEdge[1]] = g_score + self.g_scores[
+ bestEdge[0]]
+ self.f_scores[
+ bestEdge[1]] = g_score + self.compute_heuristic_cost(
+ bestEdge[1], self.goalId)
+ self.update_graph()
# visualize new edge
if animation:
- self.drawGraph(xCenter=xCenter, cBest=cBest,
- cMin=cMin, etheta=etheta, samples=self.samples.values(),
- start=firstCoord, end=secondCoord, tree=self.tree.edges)
+ self.draw_graph(xCenter=xCenter, cBest=cBest,
+ cMin=cMin, eTheta=eTheta,
+ samples=self.samples.values(),
+ start=firstCoord, end=secondCoord)
self.remove_queue(lastEdge, bestEdge)
@@ -306,14 +328,13 @@ def plan(self, animation=True):
return self.find_final_path()
def find_final_path(self):
- plan = []
- plan.append(self.goal)
+ plan = [self.goal]
currId = self.goalId
- while (currId != self.startId):
- plan.append(self.tree.nodeIdToRealWorldCoord(currId))
+ while currId != self.startId:
+ plan.append(self.tree.node_id_to_real_world_coord(currId))
try:
currId = self.nodes[currId]
- except(KeyError):
+ except KeyError:
print("cannot find Path")
return []
@@ -324,29 +345,32 @@ def find_final_path(self):
def remove_queue(self, lastEdge, bestEdge):
for edge in self.edge_queue:
- if(edge[1] == bestEdge[1]):
- if self.g_scores[edge[1]] + self.computeDistanceCost(edge[1], bestEdge[1]) >= self.g_scores[self.goalId]:
- if(lastEdge, bestEdge[1]) in self.edge_queue:
+ if edge[1] == bestEdge[1]:
+ dist_cost = self.compute_distance_cost(edge[1], bestEdge[1])
+ if self.g_scores[edge[1]] + dist_cost >= \
+ self.g_scores[self.goalId]:
+ if (lastEdge, bestEdge[1]) in self.edge_queue:
self.edge_queue.remove(
(lastEdge, bestEdge[1]))
def connect(self, start, end):
# A function which attempts to extend from a start coordinates
# to goal coordinates
- steps = int(self.computeDistanceCost(self.tree.realWorldToNodeId(
- start), self.tree.realWorldToNodeId(end)) * 10)
+ steps = int(self.compute_distance_cost(
+ self.tree.real_world_to_node_id(start),
+ self.tree.real_world_to_node_id(end)) * 10)
x = np.linspace(start[0], end[0], num=steps)
y = np.linspace(start[1], end[1], num=steps)
for i in range(len(x)):
- if(self._collisionCheck(x[i], y[i])):
- if(i == 0):
+ if self._collision_check(x[i], y[i]):
+ if i == 0:
return None
# if collision, send path until collision
return np.vstack((x[0:i], y[0:i])).transpose()
return np.vstack((x, y)).transpose()
- def _collisionCheck(self, x, y):
+ def _collision_check(self, x, y):
for (ox, oy, size) in self.obstacleList:
dx = ox - x
dy = oy - y
@@ -355,45 +379,44 @@ def _collisionCheck(self, x, y):
return True # collision
return False
- # def prune(self, c):
-
- def computeHeuristicCost(self, start_id, goal_id):
+ def compute_heuristic_cost(self, start_id, goal_id):
# Using Manhattan distance as heuristic
- start = np.array(self.tree.nodeIdToRealWorldCoord(start_id))
- goal = np.array(self.tree.nodeIdToRealWorldCoord(goal_id))
+ start = np.array(self.tree.node_id_to_real_world_coord(start_id))
+ goal = np.array(self.tree.node_id_to_real_world_coord(goal_id))
return np.linalg.norm(start - goal, 2)
- def computeDistanceCost(self, vid, xid):
+ def compute_distance_cost(self, vid, xid):
# L2 norm distance
- start = np.array(self.tree.nodeIdToRealWorldCoord(vid))
- stop = np.array(self.tree.nodeIdToRealWorldCoord(xid))
+ start = np.array(self.tree.node_id_to_real_world_coord(vid))
+ stop = np.array(self.tree.node_id_to_real_world_coord(xid))
return np.linalg.norm(stop - start, 2)
# Sample free space confined in the radius of ball R
- def informedSample(self, m, cMax, cMin, xCenter, C):
+ def informed_sample(self, m, cMax, cMin, xCenter, C):
samples = dict()
print("g_Score goal id: ", self.g_scores[self.goalId])
for i in range(m + 1):
if cMax < float('inf'):
r = [cMax / 2.0,
- math.sqrt(cMax**2 - cMin**2) / 2.0,
- math.sqrt(cMax**2 - cMin**2) / 2.0]
+ math.sqrt(cMax ** 2 - cMin ** 2) / 2.0,
+ math.sqrt(cMax ** 2 - cMin ** 2) / 2.0]
L = np.diag(r)
- xBall = self.sampleUnitBall()
+ xBall = self.sample_unit_ball()
rnd = np.dot(np.dot(C, L), xBall) + xCenter
rnd = [rnd[(0, 0)], rnd[(1, 0)]]
- random_id = self.tree.realWorldToNodeId(rnd)
+ random_id = self.tree.real_world_to_node_id(rnd)
samples[random_id] = rnd
else:
- rnd = self.sampleFreeSpace()
- random_id = self.tree.realWorldToNodeId(rnd)
+ rnd = self.sample_free_space()
+ random_id = self.tree.real_world_to_node_id(rnd)
samples[random_id] = rnd
return samples
# Sample point in a unit ball
- def sampleUnitBall(self):
+ @staticmethod
+ def sample_unit_ball():
a = random.random()
b = random.random()
@@ -404,63 +427,70 @@ def sampleUnitBall(self):
b * math.sin(2 * math.pi * a / b))
return np.array([[sample[0]], [sample[1]], [0]])
- def sampleFreeSpace(self):
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand)]
+ def sample_free_space(self):
+ rnd = [random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand)]
return rnd
- def bestVertexQueueValue(self):
- if(len(self.vertex_queue) == 0):
+ def best_vertex_queue_value(self):
+ if len(self.vertex_queue) == 0:
return float('inf')
values = [self.g_scores[v]
- + self.computeHeuristicCost(v, self.goalId) for v in self.vertex_queue]
+ + self.compute_heuristic_cost(v, self.goalId) for v in
+ self.vertex_queue]
values.sort()
return values[0]
- def bestEdgeQueueValue(self):
- if(len(self.edge_queue) == 0):
+ def best_edge_queue_value(self):
+ if len(self.edge_queue) == 0:
return float('inf')
# return the best value in the queue by score g_tau[v] + c(v,x) + h(x)
- values = [self.g_scores[e[0]] + self.computeDistanceCost(e[0], e[1])
- + self.computeHeuristicCost(e[1], self.goalId) for e in self.edge_queue]
+ values = [self.g_scores[e[0]] + self.compute_distance_cost(e[0], e[1])
+ + self.compute_heuristic_cost(e[1], self.goalId) for e in
+ self.edge_queue]
values.sort(reverse=True)
return values[0]
- def bestInVertexQueue(self):
+ def best_in_vertex_queue(self):
# return the best value in the vertex queue
- v_plus_vals = [(v, self.g_scores[v] + self.computeHeuristicCost(v, self.goalId))
- for v in self.vertex_queue]
- v_plus_vals = sorted(v_plus_vals, key=lambda x: x[1])
- # print(v_plus_vals)
- return v_plus_vals[0][0]
-
- def bestInEdgeQueue(self):
- e_and_values = [(e[0], e[1], self.g_scores[e[0]] + self.computeDistanceCost(
- e[0], e[1]) + self.computeHeuristicCost(e[1], self.goalId)) for e in self.edge_queue]
+ v_plus_values = [(v, self.g_scores[v] +
+ self.compute_heuristic_cost(v, self.goalId))
+ for v in self.vertex_queue]
+ v_plus_values = sorted(v_plus_values, key=lambda x: x[1])
+ # print(v_plus_values)
+ return v_plus_values[0][0]
+
+ def best_in_edge_queue(self):
+ e_and_values = [
+ (e[0], e[1], self.g_scores[e[0]] + self.compute_distance_cost(
+ e[0], e[1]) + self.compute_heuristic_cost(e[1], self.goalId))
+ for e in self.edge_queue]
e_and_values = sorted(e_and_values, key=lambda x: x[2])
- return (e_and_values[0][0], e_and_values[0][1])
+ return e_and_values[0][0], e_and_values[0][1]
- def expandVertex(self, vid):
+ def expand_vertex(self, vid):
self.vertex_queue.remove(vid)
# get the coordinates for given vid
- currCoord = np.array(self.tree.nodeIdToRealWorldCoord(vid))
+ currCoord = np.array(self.tree.node_id_to_real_world_coord(vid))
# get the nearest value in vertex for every one in samples where difference is
# less than the radius
- neigbors = []
- for sid, scoord in self.samples.items():
- scoord = np.array(scoord)
- if(np.linalg.norm(scoord - currCoord, 2) <= self.r and sid != vid):
- neigbors.append((sid, scoord))
+ neighbors = []
+ for sid, s_coord in self.samples.items():
+ s_coord = np.array(s_coord)
+ if np.linalg.norm(s_coord - currCoord, 2) <= self.r and sid != vid:
+ neighbors.append((sid, s_coord))
# add an edge to the edge queue is the path might improve the solution
- for neighbor in neigbors:
+ for neighbor in neighbors:
sid = neighbor[0]
- estimated_f_score = self.computeDistanceCost(
- self.startId, vid) + self.computeHeuristicCost(sid, self.goalId) + self.computeDistanceCost(vid, sid)
+ h_cost = self.compute_heuristic_cost(sid, self.goalId)
+ estimated_f_score = self.compute_distance_cost(
+ self.startId, vid) + h_cost + self.compute_distance_cost(vid,
+ sid)
if estimated_f_score < self.g_scores[self.goalId]:
self.edge_queue.append((vid, sid))
@@ -469,22 +499,26 @@ def expandVertex(self, vid):
def add_vertex_to_edge_queue(self, vid, currCoord):
if vid not in self.old_vertices:
- neigbors = []
+ neighbors = []
for v, edges in self.tree.vertices.items():
- if v != vid and (v, vid) not in self.edge_queue and (vid, v) not in self.edge_queue:
- vcoord = self.tree.nodeIdToRealWorldCoord(v)
- if(np.linalg.norm(vcoord - currCoord, 2) <= self.r):
- neigbors.append((vid, vcoord))
+ if v != vid and (v, vid) not in self.edge_queue and \
+ (vid, v) not in self.edge_queue:
+ v_coord = self.tree.node_id_to_real_world_coord(v)
+ if np.linalg.norm(currCoord - v_coord, 2) <= self.r:
+ neighbors.append((vid, v_coord))
- for neighbor in neigbors:
+ for neighbor in neighbors:
sid = neighbor[0]
- estimated_f_score = self.computeDistanceCost(self.startId, vid) + \
- self.computeDistanceCost(
- vid, sid) + self.computeHeuristicCost(sid, self.goalId)
- if estimated_f_score < self.g_scores[self.goalId] and (self.g_scores[vid] + self.computeDistanceCost(vid, sid)) < self.g_scores[sid]:
+ estimated_f_score = self.compute_distance_cost(
+ self.startId, vid) + self.compute_distance_cost(
+ vid, sid) + self.compute_heuristic_cost(sid, self.goalId)
+ if estimated_f_score < self.g_scores[self.goalId] and (
+ self.g_scores[vid] +
+ self.compute_distance_cost(vid, sid)) < \
+ self.g_scores[sid]:
self.edge_queue.append((vid, sid))
- def updateGraph(self):
+ def update_graph(self):
closedSet = []
openSet = []
currId = self.startId
@@ -498,44 +532,48 @@ def updateGraph(self):
openSet.remove(currId)
# Check if we're at the goal
- if(currId == self.goalId):
- self.nodes[self.goalId]
+ if currId == self.goalId:
break
- if(currId not in closedSet):
+ if currId not in closedSet:
closedSet.append(currId)
# find a non visited successor to the current node
successors = self.tree.vertices[currId]
- for succesor in successors:
- if(succesor in closedSet):
+ for successor in successors:
+ if successor in closedSet:
continue
else:
- # claculate tentative g score
+ # calculate tentative g score
g_score = self.g_scores[currId] + \
- self.computeDistanceCost(currId, succesor)
- if succesor not in openSet:
+ self.compute_distance_cost(currId, successor)
+ if successor not in openSet:
# add the successor to open set
- openSet.append(succesor)
- elif g_score >= self.g_scores[succesor]:
+ openSet.append(successor)
+ elif g_score >= self.g_scores[successor]:
continue
# update g and f scores
- self.g_scores[succesor] = g_score
- self.f_scores[succesor] = g_score + \
- self.computeHeuristicCost(succesor, self.goalId)
+ self.g_scores[successor] = g_score
+ self.f_scores[
+ successor] = g_score + self.compute_heuristic_cost(
+ successor, self.goalId)
# store the parent and child
- self.nodes[succesor] = currId
+ self.nodes[successor] = currId
- def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None,
- samples=None, start=None, end=None, tree=None):
+ def draw_graph(self, xCenter=None, cBest=None, cMin=None, eTheta=None,
+ samples=None, start=None, end=None):
plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
for rnd in samples:
if rnd is not None:
plt.plot(rnd[0], rnd[1], "^k")
if cBest != float('inf'):
- self.plot_ellipse(xCenter, cBest, cMin, etheta)
+ self.plot_ellipse(xCenter, cBest, cMin, eTheta)
if start is not None and end is not None:
plt.plot([start[0], start[1]], [end[0], end[1]], "-g")
@@ -549,11 +587,12 @@ def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None,
plt.grid(True)
plt.pause(0.01)
- def plot_ellipse(self, xCenter, cBest, cMin, etheta): # pragma: no cover
+ @staticmethod
+ def plot_ellipse(xCenter, cBest, cMin, eTheta): # pragma: no cover
- a = math.sqrt(cBest**2 - cMin**2) / 2.0
+ a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0
b = cBest / 2.0
- angle = math.pi / 2.0 - etheta
+ angle = math.pi / 2.0 - eTheta
cx = xCenter[0]
cy = xCenter[1]
diff --git a/PathPlanning/BezierPath/bezier_path.py b/PathPlanning/BezierPath/bezier_path.py
index fb6050d98a..46faf1f310 100644
--- a/PathPlanning/BezierPath/bezier_path.py
+++ b/PathPlanning/BezierPath/bezier_path.py
@@ -1,14 +1,14 @@
"""
-Path Planning with Bezier curve.
+Path planning with Bezier curve.
author: Atsushi Sakai(@Atsushi_twi)
"""
-import scipy.special
-import numpy as np
import matplotlib.pyplot as plt
+import numpy as np
+import scipy.special
show_animation = True
@@ -26,7 +26,7 @@ def calc_4points_bezier_path(sx, sy, syaw, ex, ey, eyaw, offset):
:param offset: (float)
:return: (numpy array, numpy array)
"""
- dist = np.sqrt((sx - ex) ** 2 + (sy - ey) ** 2) / offset
+ dist = np.hypot(sx - ex, sy - ey) / offset
control_points = np.array(
[[sx, sy],
[sx + dist * np.cos(syaw), sy + dist * np.sin(syaw)],
diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py
new file mode 100644
index 0000000000..5387cca1ad
--- /dev/null
+++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py
@@ -0,0 +1,347 @@
+"""
+
+Bidirectional A* grid planning
+
+author: Erwin Lejeune (@spida_rwin)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/Bidirectional_search)
+
+"""
+
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class BidirectionalAStarPlanner:
+
+ def __init__(self, ox, oy, resolution, rr):
+ """
+ Initialize grid map for a star planning
+
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ self.min_x, self.min_y = None, None
+ self.max_x, self.max_y = None, None
+ self.x_width, self.y_width, self.obstacle_map = None, None, None
+ self.resolution = resolution
+ self.rr = rr
+ self.calc_obstacle_map(ox, oy)
+ self.motion = self.get_motion_model()
+
+ class Node:
+ def __init__(self, x, y, cost, parent_index):
+ self.x = x # index of grid
+ self.y = y # index of grid
+ self.cost = cost
+ self.parent_index = parent_index
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
+
+ def planning(self, sx, sy, gx, gy):
+ """
+ Bidirectional A star path search
+
+ input:
+ s_x: start x position [m]
+ s_y: start y position [m]
+ gx: goal x position [m]
+ gy: goal y position [m]
+
+ output:
+ rx: x position list of the final path
+ ry: y position list of the final path
+ """
+
+ start_node = self.Node(self.calc_xy_index(sx, self.min_x),
+ self.calc_xy_index(sy, self.min_y), 0.0, -1)
+ goal_node = self.Node(self.calc_xy_index(gx, self.min_x),
+ self.calc_xy_index(gy, self.min_y), 0.0, -1)
+
+ open_set_A, closed_set_A = dict(), dict()
+ open_set_B, closed_set_B = dict(), dict()
+ open_set_A[self.calc_grid_index(start_node)] = start_node
+ open_set_B[self.calc_grid_index(goal_node)] = goal_node
+
+ current_A = start_node
+ current_B = goal_node
+ meet_point_A, meet_point_B = None, None
+
+ while True:
+ if len(open_set_A) == 0:
+ print("Open set A is empty..")
+ break
+
+ if len(open_set_B) == 0:
+ print("Open set B is empty..")
+ break
+
+ c_id_A = min(
+ open_set_A,
+ key=lambda o: self.find_total_cost(open_set_A, o, current_B))
+
+ current_A = open_set_A[c_id_A]
+
+ c_id_B = min(
+ open_set_B,
+ key=lambda o: self.find_total_cost(open_set_B, o, current_A))
+
+ current_B = open_set_B[c_id_B]
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(self.calc_grid_position(current_A.x, self.min_x),
+ self.calc_grid_position(current_A.y, self.min_y),
+ "xc")
+ plt.plot(self.calc_grid_position(current_B.x, self.min_x),
+ self.calc_grid_position(current_B.y, self.min_y),
+ "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if len(closed_set_A.keys()) % 10 == 0:
+ plt.pause(0.001)
+
+ if current_A.x == current_B.x and current_A.y == current_B.y:
+ print("Found goal")
+ meet_point_A = current_A
+ meet_point_B = current_B
+ break
+
+ # Remove the item from the open set
+ del open_set_A[c_id_A]
+ del open_set_B[c_id_B]
+
+ # Add it to the closed set
+ closed_set_A[c_id_A] = current_A
+ closed_set_B[c_id_B] = current_B
+
+ # expand_grid search grid based on motion model
+ for i, _ in enumerate(self.motion):
+
+ c_nodes = [self.Node(current_A.x + self.motion[i][0],
+ current_A.y + self.motion[i][1],
+ current_A.cost + self.motion[i][2],
+ c_id_A),
+ self.Node(current_B.x + self.motion[i][0],
+ current_B.y + self.motion[i][1],
+ current_B.cost + self.motion[i][2],
+ c_id_B)]
+
+ n_ids = [self.calc_grid_index(c_nodes[0]),
+ self.calc_grid_index(c_nodes[1])]
+
+ # If the node is not safe, do nothing
+ continue_ = self.check_nodes_and_sets(c_nodes, closed_set_A,
+ closed_set_B, n_ids)
+
+ if not continue_[0]:
+ if n_ids[0] not in open_set_A:
+ # discovered a new node
+ open_set_A[n_ids[0]] = c_nodes[0]
+ else:
+ if open_set_A[n_ids[0]].cost > c_nodes[0].cost:
+ # This path is the best until now. record it
+ open_set_A[n_ids[0]] = c_nodes[0]
+
+ if not continue_[1]:
+ if n_ids[1] not in open_set_B:
+ # discovered a new node
+ open_set_B[n_ids[1]] = c_nodes[1]
+ else:
+ if open_set_B[n_ids[1]].cost > c_nodes[1].cost:
+ # This path is the best until now. record it
+ open_set_B[n_ids[1]] = c_nodes[1]
+
+ rx, ry = self.calc_final_bidirectional_path(
+ meet_point_A, meet_point_B, closed_set_A, closed_set_B)
+
+ return rx, ry
+
+ # takes two sets and two meeting nodes and return the optimal path
+ def calc_final_bidirectional_path(self, n1, n2, setA, setB):
+ rx_A, ry_A = self.calc_final_path(n1, setA)
+ rx_B, ry_B = self.calc_final_path(n2, setB)
+
+ rx_A.reverse()
+ ry_A.reverse()
+
+ rx = rx_A + rx_B
+ ry = ry_A + ry_B
+
+ return rx, ry
+
+ def calc_final_path(self, goal_node, closed_set):
+ # generate final course
+ rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], \
+ [self.calc_grid_position(goal_node.y, self.min_y)]
+ parent_index = goal_node.parent_index
+ while parent_index != -1:
+ n = closed_set[parent_index]
+ rx.append(self.calc_grid_position(n.x, self.min_x))
+ ry.append(self.calc_grid_position(n.y, self.min_y))
+ parent_index = n.parent_index
+
+ return rx, ry
+
+ def check_nodes_and_sets(self, c_nodes, closedSet_A, closedSet_B, n_ids):
+ continue_ = [False, False]
+ if not self.verify_node(c_nodes[0]) or n_ids[0] in closedSet_A:
+ continue_[0] = True
+
+ if not self.verify_node(c_nodes[1]) or n_ids[1] in closedSet_B:
+ continue_[1] = True
+
+ return continue_
+
+ @staticmethod
+ def calc_heuristic(n1, n2):
+ w = 1.0 # weight of heuristic
+ d = w * math.hypot(n1.x - n2.x, n1.y - n2.y)
+ return d
+
+ def find_total_cost(self, open_set, lambda_, n1):
+ g_cost = open_set[lambda_].cost
+ h_cost = self.calc_heuristic(n1, open_set[lambda_])
+ f_cost = g_cost + h_cost
+ return f_cost
+
+ def calc_grid_position(self, index, min_position):
+ """
+ calc grid position
+
+ :param index:
+ :param min_position:
+ :return:
+ """
+ pos = index * self.resolution + min_position
+ return pos
+
+ def calc_xy_index(self, position, min_pos):
+ return round((position - min_pos) / self.resolution)
+
+ def calc_grid_index(self, node):
+ return (node.y - self.min_y) * self.x_width + (node.x - self.min_x)
+
+ def verify_node(self, node):
+ px = self.calc_grid_position(node.x, self.min_x)
+ py = self.calc_grid_position(node.y, self.min_y)
+
+ if px < self.min_x:
+ return False
+ elif py < self.min_y:
+ return False
+ elif px >= self.max_x:
+ return False
+ elif py >= self.max_y:
+ return False
+
+ # collision check
+ if self.obstacle_map[node.x][node.y]:
+ return False
+
+ return True
+
+ def calc_obstacle_map(self, ox, oy):
+
+ self.min_x = round(min(ox))
+ self.min_y = round(min(oy))
+ self.max_x = round(max(ox))
+ self.max_y = round(max(oy))
+ print("min_x:", self.min_x)
+ print("min_y:", self.min_y)
+ print("max_x:", self.max_x)
+ print("max_y:", self.max_y)
+
+ self.x_width = round((self.max_x - self.min_x) / self.resolution)
+ self.y_width = round((self.max_y - self.min_y) / self.resolution)
+ print("x_width:", self.x_width)
+ print("y_width:", self.y_width)
+
+ # obstacle map generation
+ self.obstacle_map = [[False for _ in range(self.y_width)]
+ for _ in range(self.x_width)]
+ for ix in range(self.x_width):
+ x = self.calc_grid_position(ix, self.min_x)
+ for iy in range(self.y_width):
+ y = self.calc_grid_position(iy, self.min_y)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.rr:
+ self.obstacle_map[ix][iy] = True
+ break
+
+ @staticmethod
+ def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx = 10.0 # [m]
+ sy = 10.0 # [m]
+ gx = 50.0 # [m]
+ gy = 50.0 # [m]
+ grid_size = 2.0 # [m]
+ robot_radius = 1.0 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation: # pragma: no cover
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "ob")
+ plt.grid(True)
+ plt.axis("equal")
+
+ bidir_a_star = BidirectionalAStarPlanner(ox, oy, grid_size, robot_radius)
+ rx, ry = bidir_a_star.planning(sx, sy, gx, gy)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(.0001)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py
new file mode 100644
index 0000000000..60a8c5e170
--- /dev/null
+++ b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py
@@ -0,0 +1,317 @@
+"""
+
+Bidirectional Breadth-First grid planning
+
+author: Erwin Lejeune (@spida_rwin)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-first_search)
+
+"""
+
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class BidirectionalBreadthFirstSearchPlanner:
+
+ def __init__(self, ox, oy, resolution, rr):
+ """
+ Initialize grid map for bfs planning
+
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ self.min_x, self.min_y = None, None
+ self.max_x, self.max_y = None, None
+ self.x_width, self.y_width, self.obstacle_map = None, None, None
+ self.resolution = resolution
+ self.rr = rr
+ self.calc_obstacle_map(ox, oy)
+ self.motion = self.get_motion_model()
+
+ class Node:
+ def __init__(self, x, y, cost, parent_index, parent):
+ self.x = x # index of grid
+ self.y = y # index of grid
+ self.cost = cost
+ self.parent_index = parent_index
+ self.parent = parent
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
+
+ def planning(self, sx, sy, gx, gy):
+ """
+ Bidirectional Breadth First search based planning
+
+ input:
+ s_x: start x position [m]
+ s_y: start y position [m]
+ gx: goal x position [m]
+ gy: goal y position [m]
+
+ output:
+ rx: x position list of the final path
+ ry: y position list of the final path
+ """
+
+ start_node = self.Node(self.calc_xy_index(sx, self.min_x),
+ self.calc_xy_index(sy, self.min_y), 0.0, -1,
+ None)
+ goal_node = self.Node(self.calc_xy_index(gx, self.min_x),
+ self.calc_xy_index(gy, self.min_y), 0.0, -1,
+ None)
+
+ open_set_A, closed_set_A = dict(), dict()
+ open_set_B, closed_set_B = dict(), dict()
+ open_set_B[self.calc_grid_index(goal_node)] = goal_node
+ open_set_A[self.calc_grid_index(start_node)] = start_node
+
+ meet_point_A, meet_point_B = None, None
+
+ while True:
+ if len(open_set_A) == 0:
+ print("Open set A is empty..")
+ break
+
+ if len(open_set_B) == 0:
+ print("Open set B is empty")
+ break
+
+ current_A = open_set_A.pop(list(open_set_A.keys())[0])
+ current_B = open_set_B.pop(list(open_set_B.keys())[0])
+
+ c_id_A = self.calc_grid_index(current_A)
+ c_id_B = self.calc_grid_index(current_B)
+
+ closed_set_A[c_id_A] = current_A
+ closed_set_B[c_id_B] = current_B
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(self.calc_grid_position(current_A.x, self.min_x),
+ self.calc_grid_position(current_A.y, self.min_y),
+ "xc")
+ plt.plot(self.calc_grid_position(current_B.x, self.min_x),
+ self.calc_grid_position(current_B.y, self.min_y),
+ "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if len(closed_set_A.keys()) % 10 == 0:
+ plt.pause(0.001)
+
+ if c_id_A in closed_set_B:
+ print("Find goal")
+ meet_point_A = closed_set_A[c_id_A]
+ meet_point_B = closed_set_B[c_id_A]
+ break
+
+ elif c_id_B in closed_set_A:
+ print("Find goal")
+ meet_point_A = closed_set_A[c_id_B]
+ meet_point_B = closed_set_B[c_id_B]
+ break
+
+ # expand_grid search grid based on motion model
+ for i, _ in enumerate(self.motion):
+ breakA = False
+ breakB = False
+
+ node_A = self.Node(current_A.x + self.motion[i][0],
+ current_A.y + self.motion[i][1],
+ current_A.cost + self.motion[i][2],
+ c_id_A, None)
+ node_B = self.Node(current_B.x + self.motion[i][0],
+ current_B.y + self.motion[i][1],
+ current_B.cost + self.motion[i][2],
+ c_id_B, None)
+
+ n_id_A = self.calc_grid_index(node_A)
+ n_id_B = self.calc_grid_index(node_B)
+
+ # If the node is not safe, do nothing
+ if not self.verify_node(node_A):
+ breakA = True
+
+ if not self.verify_node(node_B):
+ breakB = True
+
+ if (n_id_A not in closed_set_A) and \
+ (n_id_A not in open_set_A) and (not breakA):
+ node_A.parent = current_A
+ open_set_A[n_id_A] = node_A
+
+ if (n_id_B not in closed_set_B) and \
+ (n_id_B not in open_set_B) and (not breakB):
+ node_B.parent = current_B
+ open_set_B[n_id_B] = node_B
+
+ rx, ry = self.calc_final_path_bidir(
+ meet_point_A, meet_point_B, closed_set_A, closed_set_B)
+ return rx, ry
+
+ # takes both set and meeting nodes and calculate optimal path
+ def calc_final_path_bidir(self, n1, n2, setA, setB):
+ rxA, ryA = self.calc_final_path(n1, setA)
+ rxB, ryB = self.calc_final_path(n2, setB)
+
+ rxA.reverse()
+ ryA.reverse()
+
+ rx = rxA + rxB
+ ry = ryA + ryB
+
+ return rx, ry
+
+ def calc_final_path(self, goal_node, closed_set):
+ # generate final course
+ rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [
+ self.calc_grid_position(goal_node.y, self.min_y)]
+ n = closed_set[goal_node.parent_index]
+ while n is not None:
+ rx.append(self.calc_grid_position(n.x, self.min_x))
+ ry.append(self.calc_grid_position(n.y, self.min_y))
+ n = n.parent
+
+ return rx, ry
+
+ def calc_grid_position(self, index, min_position):
+ """
+ calc grid position
+
+ :param index:
+ :param min_position:
+ :return:
+ """
+ pos = index * self.resolution + min_position
+ return pos
+
+ def calc_xy_index(self, position, min_pos):
+ return round((position - min_pos) / self.resolution)
+
+ def calc_grid_index(self, node):
+ return (node.y - self.min_y) * self.x_width + (node.x - self.min_x)
+
+ def verify_node(self, node):
+ px = self.calc_grid_position(node.x, self.min_x)
+ py = self.calc_grid_position(node.y, self.min_y)
+
+ if px < self.min_x:
+ return False
+ elif py < self.min_y:
+ return False
+ elif px >= self.max_x:
+ return False
+ elif py >= self.max_y:
+ return False
+
+ # collision check
+ if self.obstacle_map[node.x][node.y]:
+ return False
+
+ return True
+
+ def calc_obstacle_map(self, ox, oy):
+
+ self.min_x = round(min(ox))
+ self.min_y = round(min(oy))
+ self.max_x = round(max(ox))
+ self.max_y = round(max(oy))
+ print("min_x:", self.min_x)
+ print("min_y:", self.min_y)
+ print("max_x:", self.max_x)
+ print("max_y:", self.max_y)
+
+ self.x_width = round((self.max_x - self.min_x) / self.resolution)
+ self.y_width = round((self.max_y - self.min_y) / self.resolution)
+ print("x_width:", self.x_width)
+ print("y_width:", self.y_width)
+
+ # obstacle map generation
+ self.obstacle_map = [[False for _ in range(self.y_width)]
+ for _ in range(self.x_width)]
+ for ix in range(self.x_width):
+ x = self.calc_grid_position(ix, self.min_x)
+ for iy in range(self.y_width):
+ y = self.calc_grid_position(iy, self.min_y)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.rr:
+ self.obstacle_map[ix][iy] = True
+ break
+
+ @staticmethod
+ def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx = 10.0 # [m]
+ sy = 10.0 # [m]
+ gx = 50.0 # [m]
+ gy = 50.0 # [m]
+ grid_size = 2.0 # [m]
+ robot_radius = 1.0 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation: # pragma: no cover
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "ob")
+ plt.grid(True)
+ plt.axis("equal")
+
+ bi_bfs = BidirectionalBreadthFirstSearchPlanner(
+ ox, oy, grid_size, robot_radius)
+ rx, ry = bi_bfs.planning(sx, sy, gx, gy)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py
new file mode 100644
index 0000000000..ad994732a5
--- /dev/null
+++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py
@@ -0,0 +1,258 @@
+"""
+
+Breadth-First grid planning
+
+author: Erwin Lejeune (@spida_rwin)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-first_search)
+
+"""
+
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class BreadthFirstSearchPlanner:
+
+ def __init__(self, ox, oy, reso, rr):
+ """
+ Initialize grid map for bfs planning
+
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ self.reso = reso
+ self.rr = rr
+ self.calc_obstacle_map(ox, oy)
+ self.motion = self.get_motion_model()
+
+ class Node:
+ def __init__(self, x, y, cost, parent_index, parent):
+ self.x = x # index of grid
+ self.y = y # index of grid
+ self.cost = cost
+ self.parent_index = parent_index
+ self.parent = parent
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
+
+ def planning(self, sx, sy, gx, gy):
+ """
+ Breadth First search based planning
+
+ input:
+ s_x: start x position [m]
+ s_y: start y position [m]
+ gx: goal x position [m]
+ gy: goal y position [m]
+
+ output:
+ rx: x position list of the final path
+ ry: y position list of the final path
+ """
+
+ nstart = self.Node(self.calc_xyindex(sx, self.minx),
+ self.calc_xyindex(sy, self.miny), 0.0, -1, None)
+ ngoal = self.Node(self.calc_xyindex(gx, self.minx),
+ self.calc_xyindex(gy, self.miny), 0.0, -1, None)
+
+ open_set, closed_set = dict(), dict()
+ open_set[self.calc_grid_index(nstart)] = nstart
+
+ while True:
+ if len(open_set) == 0:
+ print("Open set is empty..")
+ break
+
+ current = open_set.pop(list(open_set.keys())[0])
+
+ c_id = self.calc_grid_index(current)
+
+ closed_set[c_id] = current
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(self.calc_grid_position(current.x, self.minx),
+ self.calc_grid_position(current.y, self.miny), "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event:
+ [exit(0) if event.key == 'escape'
+ else None])
+ if len(closed_set.keys()) % 10 == 0:
+ plt.pause(0.001)
+
+ if current.x == ngoal.x and current.y == ngoal.y:
+ print("Find goal")
+ ngoal.parent_index = current.parent_index
+ ngoal.cost = current.cost
+ break
+
+ # expand_grid search grid based on motion model
+ for i, _ in enumerate(self.motion):
+ node = self.Node(current.x + self.motion[i][0],
+ current.y + self.motion[i][1],
+ current.cost + self.motion[i][2], c_id, None)
+ n_id = self.calc_grid_index(node)
+
+ # If the node is not safe, do nothing
+ if not self.verify_node(node):
+ continue
+
+ if (n_id not in closed_set) and (n_id not in open_set):
+ node.parent = current
+ open_set[n_id] = node
+
+ rx, ry = self.calc_final_path(ngoal, closed_set)
+ return rx, ry
+
+ def calc_final_path(self, ngoal, closedset):
+ # generate final course
+ rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [
+ self.calc_grid_position(ngoal.y, self.miny)]
+ n = closedset[ngoal.parent_index]
+ while n is not None:
+ rx.append(self.calc_grid_position(n.x, self.minx))
+ ry.append(self.calc_grid_position(n.y, self.miny))
+ n = n.parent
+
+ return rx, ry
+
+ def calc_grid_position(self, index, minp):
+ """
+ calc grid position
+
+ :param index:
+ :param minp:
+ :return:
+ """
+ pos = index * self.reso + minp
+ return pos
+
+ def calc_xyindex(self, position, min_pos):
+ return round((position - min_pos) / self.reso)
+
+ def calc_grid_index(self, node):
+ return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
+
+ def verify_node(self, node):
+ px = self.calc_grid_position(node.x, self.minx)
+ py = self.calc_grid_position(node.y, self.miny)
+
+ if px < self.minx:
+ return False
+ elif py < self.miny:
+ return False
+ elif px >= self.maxx:
+ return False
+ elif py >= self.maxy:
+ return False
+
+ # collision check
+ if self.obmap[node.x][node.y]:
+ return False
+
+ return True
+
+ def calc_obstacle_map(self, ox, oy):
+
+ self.minx = round(min(ox))
+ self.miny = round(min(oy))
+ self.maxx = round(max(ox))
+ self.maxy = round(max(oy))
+ print("min_x:", self.minx)
+ print("min_y:", self.miny)
+ print("max_x:", self.maxx)
+ print("max_y:", self.maxy)
+
+ self.xwidth = round((self.maxx - self.minx) / self.reso)
+ self.ywidth = round((self.maxy - self.miny) / self.reso)
+ print("x_width:", self.xwidth)
+ print("y_width:", self.ywidth)
+
+ # obstacle map generation
+ self.obmap = [[False for _ in range(self.ywidth)]
+ for _ in range(self.xwidth)]
+ for ix in range(self.xwidth):
+ x = self.calc_grid_position(ix, self.minx)
+ for iy in range(self.ywidth):
+ y = self.calc_grid_position(iy, self.miny)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.rr:
+ self.obmap[ix][iy] = True
+ break
+
+ @staticmethod
+ def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx = 10.0 # [m]
+ sy = 10.0 # [m]
+ gx = 50.0 # [m]
+ gy = 50.0 # [m]
+ grid_size = 2.0 # [m]
+ robot_radius = 1.0 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(float(i))
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(float(i))
+ for i in range(-10, 61):
+ ox.append(float(i))
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(float(i))
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(float(i))
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation: # pragma: no cover
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "xb")
+ plt.grid(True)
+ plt.axis("equal")
+
+ bfs = BreadthFirstSearchPlanner(ox, oy, grid_size, robot_radius)
+ rx, ry = bfs.planning(sx, sy, gx, gy)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/BugPlanning/bug.py b/PathPlanning/BugPlanning/bug.py
new file mode 100644
index 0000000000..34890cb55a
--- /dev/null
+++ b/PathPlanning/BugPlanning/bug.py
@@ -0,0 +1,333 @@
+"""
+Bug Planning
+author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it)
+Source: https://web.archive.org/web/20201103052224/https://sites.google.com/site/ece452bugalgorithms/
+"""
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class BugPlanner:
+ def __init__(self, start_x, start_y, goal_x, goal_y, obs_x, obs_y):
+ self.goal_x = goal_x
+ self.goal_y = goal_y
+ self.obs_x = obs_x
+ self.obs_y = obs_y
+ self.r_x = [start_x]
+ self.r_y = [start_y]
+ self.out_x = []
+ self.out_y = []
+ for o_x, o_y in zip(obs_x, obs_y):
+ for add_x, add_y in zip([1, 0, -1, -1, -1, 0, 1, 1],
+ [1, 1, 1, 0, -1, -1, -1, 0]):
+ cand_x, cand_y = o_x+add_x, o_y+add_y
+ valid_point = True
+ for _x, _y in zip(obs_x, obs_y):
+ if cand_x == _x and cand_y == _y:
+ valid_point = False
+ break
+ if valid_point:
+ self.out_x.append(cand_x), self.out_y.append(cand_y)
+
+ def mov_normal(self):
+ return self.r_x[-1] + np.sign(self.goal_x - self.r_x[-1]), \
+ self.r_y[-1] + np.sign(self.goal_y - self.r_y[-1])
+
+ def mov_to_next_obs(self, visited_x, visited_y):
+ for add_x, add_y in zip([1, 0, -1, 0], [0, 1, 0, -1]):
+ c_x, c_y = self.r_x[-1] + add_x, self.r_y[-1] + add_y
+ for _x, _y in zip(self.out_x, self.out_y):
+ use_pt = True
+ if c_x == _x and c_y == _y:
+ for v_x, v_y in zip(visited_x, visited_y):
+ if c_x == v_x and c_y == v_y:
+ use_pt = False
+ break
+ if use_pt:
+ return c_x, c_y, False
+ if not use_pt:
+ break
+ return self.r_x[-1], self.r_y[-1], True
+
+ def bug0(self):
+ """
+ Greedy algorithm where you move towards goal
+ until you hit an obstacle. Then you go around it
+ (pick an arbitrary direction), until it is possible
+ for you to start moving towards goal in a greedy manner again
+ """
+ mov_dir = 'normal'
+ cand_x, cand_y = -np.inf, -np.inf
+ if show_animation:
+ plt.plot(self.obs_x, self.obs_y, ".k")
+ plt.plot(self.r_x[-1], self.r_y[-1], "og")
+ plt.plot(self.goal_x, self.goal_y, "xb")
+ plt.plot(self.out_x, self.out_y, ".")
+ plt.grid(True)
+ plt.title('BUG 0')
+
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if self.r_x[-1] == x_ob and self.r_y[-1] == y_ob:
+ mov_dir = 'obs'
+ break
+
+ visited_x, visited_y = [], []
+ while True:
+ if self.r_x[-1] == self.goal_x and \
+ self.r_y[-1] == self.goal_y:
+ break
+ if mov_dir == 'normal':
+ cand_x, cand_y = self.mov_normal()
+ if mov_dir == 'obs':
+ cand_x, cand_y, _ = self.mov_to_next_obs(visited_x, visited_y)
+ if mov_dir == 'normal':
+ found_boundary = False
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if cand_x == x_ob and cand_y == y_ob:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x[:], visited_y[:] = [], []
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ mov_dir = 'obs'
+ found_boundary = True
+ break
+ if not found_boundary:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ elif mov_dir == 'obs':
+ can_go_normal = True
+ for x_ob, y_ob in zip(self.obs_x, self.obs_y):
+ if self.mov_normal()[0] == x_ob and \
+ self.mov_normal()[1] == y_ob:
+ can_go_normal = False
+ break
+ if can_go_normal:
+ mov_dir = 'normal'
+ else:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ if show_animation:
+ plt.plot(self.r_x, self.r_y, "-r")
+ plt.pause(0.001)
+ if show_animation:
+ plt.show()
+
+ def bug1(self):
+ """
+ Move towards goal in a greedy manner.
+ When you hit an obstacle, you go around it and
+ back to where you hit the obstacle initially.
+ Then, you go to the point on the obstacle that is
+ closest to your goal and you start moving towards
+ goal in a greedy manner from that new point.
+ """
+ mov_dir = 'normal'
+ cand_x, cand_y = -np.inf, -np.inf
+ exit_x, exit_y = -np.inf, -np.inf
+ dist = np.inf
+ back_to_start = False
+ second_round = False
+ if show_animation:
+ plt.plot(self.obs_x, self.obs_y, ".k")
+ plt.plot(self.r_x[-1], self.r_y[-1], "og")
+ plt.plot(self.goal_x, self.goal_y, "xb")
+ plt.plot(self.out_x, self.out_y, ".")
+ plt.grid(True)
+ plt.title('BUG 1')
+
+ for xob, yob in zip(self.out_x, self.out_y):
+ if self.r_x[-1] == xob and self.r_y[-1] == yob:
+ mov_dir = 'obs'
+ break
+
+ visited_x, visited_y = [], []
+ while True:
+ if self.r_x[-1] == self.goal_x and \
+ self.r_y[-1] == self.goal_y:
+ break
+ if mov_dir == 'normal':
+ cand_x, cand_y = self.mov_normal()
+ if mov_dir == 'obs':
+ cand_x, cand_y, back_to_start = \
+ self.mov_to_next_obs(visited_x, visited_y)
+ if mov_dir == 'normal':
+ found_boundary = False
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if cand_x == x_ob and cand_y == y_ob:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x[:], visited_y[:] = [], []
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ mov_dir = 'obs'
+ dist = np.inf
+ back_to_start = False
+ second_round = False
+ found_boundary = True
+ break
+ if not found_boundary:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ elif mov_dir == 'obs':
+ d = np.linalg.norm(np.array([cand_x, cand_y] -
+ np.array([self.goal_x,
+ self.goal_y])))
+ if d < dist and not second_round:
+ exit_x, exit_y = cand_x, cand_y
+ dist = d
+ if back_to_start and not second_round:
+ second_round = True
+ del self.r_x[-len(visited_x):]
+ del self.r_y[-len(visited_y):]
+ visited_x[:], visited_y[:] = [], []
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ if cand_x == exit_x and \
+ cand_y == exit_y and \
+ second_round:
+ mov_dir = 'normal'
+ if show_animation:
+ plt.plot(self.r_x, self.r_y, "-r")
+ plt.pause(0.001)
+ if show_animation:
+ plt.show()
+
+ def bug2(self):
+ """
+ Move towards goal in a greedy manner.
+ When you hit an obstacle, you go around it and
+ keep track of your distance from the goal.
+ If the distance from your goal was decreasing before
+ and now it starts increasing, that means the current
+ point is probably the closest point to the
+ goal (this may or may not be true because the algorithm
+ doesn't explore the entire boundary around the obstacle).
+ So, you depart from this point and continue towards the
+ goal in a greedy manner
+ """
+ mov_dir = 'normal'
+ cand_x, cand_y = -np.inf, -np.inf
+ if show_animation:
+ plt.plot(self.obs_x, self.obs_y, ".k")
+ plt.plot(self.r_x[-1], self.r_y[-1], "og")
+ plt.plot(self.goal_x, self.goal_y, "xb")
+ plt.plot(self.out_x, self.out_y, ".")
+
+ straight_x, straight_y = [self.r_x[-1]], [self.r_y[-1]]
+ hit_x, hit_y = [], []
+ while True:
+ if straight_x[-1] == self.goal_x and \
+ straight_y[-1] == self.goal_y:
+ break
+ c_x = straight_x[-1] + np.sign(self.goal_x - straight_x[-1])
+ c_y = straight_y[-1] + np.sign(self.goal_y - straight_y[-1])
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if c_x == x_ob and c_y == y_ob:
+ hit_x.append(c_x), hit_y.append(c_y)
+ break
+ straight_x.append(c_x), straight_y.append(c_y)
+ if show_animation:
+ plt.plot(straight_x, straight_y, ",")
+ plt.plot(hit_x, hit_y, "d")
+ plt.grid(True)
+ plt.title('BUG 2')
+
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if self.r_x[-1] == x_ob and self.r_y[-1] == y_ob:
+ mov_dir = 'obs'
+ break
+
+ visited_x, visited_y = [], []
+ while True:
+ if self.r_x[-1] == self.goal_x \
+ and self.r_y[-1] == self.goal_y:
+ break
+ if mov_dir == 'normal':
+ cand_x, cand_y = self.mov_normal()
+ if mov_dir == 'obs':
+ cand_x, cand_y, _ = self.mov_to_next_obs(visited_x, visited_y)
+ if mov_dir == 'normal':
+ found_boundary = False
+ for x_ob, y_ob in zip(self.out_x, self.out_y):
+ if cand_x == x_ob and cand_y == y_ob:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x[:], visited_y[:] = [], []
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ del hit_x[0]
+ del hit_y[0]
+ mov_dir = 'obs'
+ found_boundary = True
+ break
+ if not found_boundary:
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ elif mov_dir == 'obs':
+ self.r_x.append(cand_x), self.r_y.append(cand_y)
+ visited_x.append(cand_x), visited_y.append(cand_y)
+ for i_x, i_y in zip(range(len(hit_x)), range(len(hit_y))):
+ if cand_x == hit_x[i_x] and cand_y == hit_y[i_y]:
+ del hit_x[i_x]
+ del hit_y[i_y]
+ mov_dir = 'normal'
+ break
+ if show_animation:
+ plt.plot(self.r_x, self.r_y, "-r")
+ plt.pause(0.001)
+ if show_animation:
+ plt.show()
+
+
+def main(bug_0, bug_1, bug_2):
+ # set obstacle positions
+ o_x, o_y = [], []
+
+ s_x = 0.0
+ s_y = 0.0
+ g_x = 167.0
+ g_y = 50.0
+
+ for i in range(20, 40):
+ for j in range(20, 40):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(60, 100):
+ for j in range(40, 80):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(120, 140):
+ for j in range(80, 100):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(80, 140):
+ for j in range(0, 20):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(0, 20):
+ for j in range(60, 100):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(20, 40):
+ for j in range(80, 100):
+ o_x.append(i)
+ o_y.append(j)
+
+ for i in range(120, 160):
+ for j in range(40, 60):
+ o_x.append(i)
+ o_y.append(j)
+
+ if bug_0:
+ my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y)
+ my_Bug.bug0()
+ if bug_1:
+ my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y)
+ my_Bug.bug1()
+ if bug_2:
+ my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y)
+ my_Bug.bug2()
+
+
+if __name__ == '__main__':
+ main(bug_0=True, bug_1=False, bug_2=False)
diff --git a/PathPlanning/Catmull_RomSplinePath/blending_functions.py b/PathPlanning/Catmull_RomSplinePath/blending_functions.py
new file mode 100644
index 0000000000..f3ef5dd323
--- /dev/null
+++ b/PathPlanning/Catmull_RomSplinePath/blending_functions.py
@@ -0,0 +1,34 @@
+import numpy as np
+import matplotlib.pyplot as plt
+
+def blending_function_1(t):
+ return -t + 2*t**2 - t**3
+
+def blending_function_2(t):
+ return 2 - 5*t**2 + 3*t**3
+
+def blending_function_3(t):
+ return t + 4*t**2 - 3*t**3
+
+def blending_function_4(t):
+ return -t**2 + t**3
+
+def plot_blending_functions():
+ t = np.linspace(0, 1, 100)
+
+ plt.plot(t, blending_function_1(t), label='b1')
+ plt.plot(t, blending_function_2(t), label='b2')
+ plt.plot(t, blending_function_3(t), label='b3')
+ plt.plot(t, blending_function_4(t), label='b4')
+
+ plt.title("Catmull-Rom Blending Functions")
+ plt.xlabel("t")
+ plt.ylabel("Value")
+ plt.legend()
+ plt.grid(True)
+ plt.axhline(y=0, color='k', linestyle='--')
+ plt.axvline(x=0, color='k', linestyle='--')
+ plt.show()
+
+if __name__ == "__main__":
+ plot_blending_functions()
\ No newline at end of file
diff --git a/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py b/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py
new file mode 100644
index 0000000000..79916330c9
--- /dev/null
+++ b/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py
@@ -0,0 +1,86 @@
+"""
+Path Planner with Catmull-Rom Spline
+Author: Surabhi Gupta (@this_is_surabhi)
+Source: http://graphics.cs.cmu.edu/nsp/course/15-462/Fall04/assts/catmullRom.pdf
+"""
+
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+def catmull_rom_point(t, p0, p1, p2, p3):
+ """
+ Parameters
+ ----------
+ t : float
+ Parameter value (0 <= t <= 1) (0 <= t <= 1)
+ p0, p1, p2, p3 : np.ndarray
+ Control points for the spline segment
+
+ Returns
+ -------
+ np.ndarray
+ Calculated point on the spline
+ """
+ return 0.5 * ((2 * p1) +
+ (-p0 + p2) * t +
+ (2 * p0 - 5 * p1 + 4 * p2 - p3) * t**2 +
+ (-p0 + 3 * p1 - 3 * p2 + p3) * t**3)
+
+
+def catmull_rom_spline(control_points, num_points):
+ """
+ Parameters
+ ----------
+ control_points : list
+ List of control points
+ num_points : int
+ Number of points to generate on the spline
+
+ Returns
+ -------
+ tuple
+ x and y coordinates of the spline points
+ """
+ t_vals = np.linspace(0, 1, num_points)
+ spline_points = []
+
+ control_points = np.array(control_points)
+
+ for i in range(len(control_points) - 1):
+ if i == 0:
+ p1, p2, p3 = control_points[i:i+3]
+ p0 = p1
+ elif i == len(control_points) - 2:
+ p0, p1, p2 = control_points[i-1:i+2]
+ p3 = p2
+ else:
+ p0, p1, p2, p3 = control_points[i-1:i+3]
+
+ for t in t_vals:
+ point = catmull_rom_point(t, p0, p1, p2, p3)
+ spline_points.append(point)
+
+ return np.array(spline_points).T
+
+
+def main():
+ print(__file__ + " start!!")
+
+ way_points = [[-1.0, -2.0], [1.0, -1.0], [3.0, -2.0], [4.0, -1.0], [3.0, 1.0], [1.0, 2.0], [0.0, 2.0]]
+ n_course_point = 100
+ spline_x, spline_y = catmull_rom_spline(way_points, n_course_point)
+
+ plt.plot(spline_x,spline_y, '-r', label="Catmull-Rom Spline Path")
+ plt.plot(np.array(way_points).T[0], np.array(way_points).T[1], '-og', label="Way points")
+ plt.title("Catmull-Rom Spline Path")
+ plt.grid(True)
+ plt.legend()
+ plt.axis("equal")
+ plt.show()
+
+if __name__ == '__main__':
+ main()
\ No newline at end of file
diff --git a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py
index 927fcd9448..01ab8349a9 100644
--- a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py
+++ b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py
@@ -1,106 +1,57 @@
"""
-Path Planning Sample Code with Closed loop RRT for car like robot.
+
+Path planning Sample Code with Closed loop RRT for car like robot.
author: AtsushiSakai(@Atsushi_twi)
"""
-
-import random
-import math
-import copy
-import numpy as np
-import pure_pursuit
import matplotlib.pyplot as plt
+import numpy as np
import sys
-import os
-sys.path.append(os.path.dirname(
- os.path.abspath(__file__)) + "/../ReedsSheppPath/")
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
-try:
- import reeds_shepp_path_planning
- import unicycle_model
-except:
- raise
+from ClosedLoopRRTStar import pure_pursuit
+from ClosedLoopRRTStar import unicycle_model
+from ReedsSheppPath import reeds_shepp_path_planning
+from RRTStarReedsShepp.rrt_star_reeds_shepp import RRTStarReedsShepp
show_animation = True
-target_speed = 10.0 / 3.6
-STEP_SIZE = 0.1
-
-
-class RRT():
+class ClosedLoopRRTStar(RRTStarReedsShepp):
"""
- Class for RRT Planning
+ Class for Closed loop RRT star planning
"""
- def __init__(self, start, goal, obstacleList, randArea,
- maxIter=200):
- """
- Setting Parameter
-
- start:Start Position [x,y]
- goal:Goal Position [x,y]
- obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
-
- """
- self.start = Node(start[0], start[1], start[2])
- self.end = Node(goal[0], goal[1], goal[2])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.obstacleList = obstacleList
- self.maxIter = maxIter
-
- def try_goal_path(self):
-
- goal = Node(self.end.x, self.end.y, self.end.yaw)
-
- newNode = self.steer(goal, len(self.nodeList) - 1)
- if newNode is None:
- return
-
- if self.CollisionCheck(newNode, self.obstacleList):
- # print("goal path is OK")
- self.nodeList.append(newNode)
-
- def Planning(self, animation=True):
+ def __init__(self, start, goal, obstacle_list, rand_area,
+ max_iter=200,
+ connect_circle_dist=50.0,
+ robot_radius=0.0
+ ):
+ super().__init__(start, goal, obstacle_list, rand_area,
+ max_iter=max_iter,
+ connect_circle_dist=connect_circle_dist,
+ robot_radius=robot_radius
+ )
+
+ self.target_speed = 10.0 / 3.6
+ self.yaw_th = np.deg2rad(3.0)
+ self.xy_th = 0.5
+ self.invalid_travel_ratio = 5.0
+
+ def planning(self, animation=True):
"""
- Pathplanning
+ do planning
animation: flag for animation on or off
"""
-
- self.nodeList = [self.start]
-
- self.try_goal_path()
-
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.GetNearestListIndex(self.nodeList, rnd)
-
- newNode = self.steer(rnd, nind)
- # print(newNode.cost)
- if newNode is None:
- continue
-
- if self.CollisionCheck(newNode, self.obstacleList):
- nearinds = self.find_near_nodes(newNode)
- newNode = self.choose_parent(newNode, nearinds)
- if newNode is None:
- continue
-
- self.nodeList.append(newNode)
- self.rewire(newNode, nearinds)
-
- self.try_goal_path()
-
- if animation and i % 5 == 0:
- self.DrawGraph(rnd=rnd)
+ # planning with RRTStarReedsShepp
+ super().planning(animation=animation)
# generate coruse
- path_indexs = self.get_best_last_indexs()
+ path_indexs = self.get_goal_indexes()
flag, x, y, yaw, v, t, a, d = self.search_best_feasible_path(
path_indexs)
@@ -113,11 +64,11 @@ def search_best_feasible_path(self, path_indexs):
best_time = float("inf")
- fx = None
+ fx, fy, fyaw, fv, ft, fa, fd = None, None, None, None, None, None, None
# pure pursuit tracking
for ind in path_indexs:
- path = self.gen_final_course(ind)
+ path = self.generate_final_course(ind)
flag, x, y, yaw, v, t, a, d = self.check_tracking_path_is_feasible(
path)
@@ -139,121 +90,49 @@ def search_best_feasible_path(self, path_indexs):
return False, None, None, None, None, None, None, None
def check_tracking_path_is_feasible(self, path):
- # print("check_tracking_path_is_feasible")
- cx = np.array(path[:, 0])
- cy = np.array(path[:, 1])
- cyaw = np.array(path[:, 2])
+ cx = np.array([state[0] for state in path])[::-1]
+ cy = np.array([state[1] for state in path])[::-1]
+ cyaw = np.array([state[2] for state in path])[::-1]
goal = [cx[-1], cy[-1], cyaw[-1]]
cx, cy, cyaw = pure_pursuit.extend_path(cx, cy, cyaw)
speed_profile = pure_pursuit.calc_speed_profile(
- cx, cy, cyaw, target_speed)
+ cx, cy, cyaw, self.target_speed)
t, x, y, yaw, v, a, d, find_goal = pure_pursuit.closed_loop_prediction(
cx, cy, cyaw, speed_profile, goal)
- yaw = [self.pi_2_pi(iyaw) for iyaw in yaw]
+ yaw = [reeds_shepp_path_planning.pi_2_pi(iyaw) for iyaw in yaw]
if not find_goal:
print("cannot reach goal")
- if abs(yaw[-1] - goal[2]) >= math.pi / 4.0:
+ if abs(yaw[-1] - goal[2]) >= self.yaw_th * 10.0:
print("final angle is bad")
find_goal = False
- travel = sum([abs(iv) * unicycle_model.dt for iv in v])
- # print(travel)
- origin_travel = sum([math.sqrt(dx ** 2 + dy ** 2)
- for (dx, dy) in zip(np.diff(cx), np.diff(cy))])
- # print(origin_travel)
+ travel = unicycle_model.dt * sum(np.abs(v))
+ origin_travel = sum(np.hypot(np.diff(cx), np.diff(cy)))
- if (travel / origin_travel) >= 5.0:
+ if (travel / origin_travel) >= self.invalid_travel_ratio:
print("path is too long")
find_goal = False
- if not self.CollisionCheckWithXY(x, y, self.obstacleList):
+ tmp_node = self.Node(x, y, 0)
+ tmp_node.path_x = x
+ tmp_node.path_y = y
+ if not self.check_collision(
+ tmp_node, self.obstacle_list, self.robot_radius):
print("This path is collision")
find_goal = False
return find_goal, x, y, yaw, v, t, a, d
- def choose_parent(self, newNode, nearinds):
- if not nearinds:
- return newNode
-
- dlist = []
- for i in nearinds:
- tNode = self.steer(newNode, i)
- if tNode is None:
- continue
-
- if self.CollisionCheck(tNode, self.obstacleList):
- dlist.append(tNode.cost)
- else:
- dlist.append(float("inf"))
-
- mincost = min(dlist)
- minind = nearinds[dlist.index(mincost)]
-
- if mincost == float("inf"):
- print("mincost is inf")
- return newNode
-
- newNode = self.steer(newNode, minind)
- if newNode is None:
- return None
-
- return newNode
-
- def pi_2_pi(self, angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
-
- def steer(self, rnd, nind):
- # print(rnd)
-
- nearestNode = self.nodeList[nind]
-
- px, py, pyaw, mode, clen = reeds_shepp_path_planning.reeds_shepp_path_planning(
- nearestNode.x, nearestNode.y, nearestNode.yaw,
- rnd.x, rnd.y, rnd.yaw, unicycle_model.curvature_max, STEP_SIZE)
-
- if px is None:
- return None
-
- newNode = copy.deepcopy(nearestNode)
- newNode.x = px[-1]
- newNode.y = py[-1]
- newNode.yaw = pyaw[-1]
-
- newNode.path_x = px
- newNode.path_y = py
- newNode.path_yaw = pyaw
- newNode.cost += sum([abs(c) for c in clen])
- newNode.parent = nind
-
- return newNode
-
- def get_random_point(self):
-
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand),
- random.uniform(-math.pi, math.pi)
- ]
-
- node = Node(rnd[0], rnd[1], rnd[2])
-
- return node
-
- def get_best_last_indexs(self):
- # print("get_best_last_index")
-
- YAWTH = np.deg2rad(1.0)
- XYTH = 0.5
-
+ def get_goal_indexes(self):
goalinds = []
- for (i, node) in enumerate(self.nodeList):
- if self.calc_dist_to_goal(node.x, node.y) <= XYTH:
+ for (i, node) in enumerate(self.node_list):
+ if self.calc_dist_to_goal(node.x, node.y) <= self.xy_th:
goalinds.append(i)
print("OK XY TH num is")
print(len(goalinds))
@@ -261,136 +140,18 @@ def get_best_last_indexs(self):
# angle check
fgoalinds = []
for i in goalinds:
- if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH:
+ if abs(self.node_list[i].yaw - self.end.yaw) <= self.yaw_th:
fgoalinds.append(i)
print("OK YAW TH num is")
print(len(fgoalinds))
return fgoalinds
- def gen_final_course(self, goalind):
- path = [[self.end.x, self.end.y, self.end.yaw]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
- path_x = reversed(node.path_x)
- path_y = reversed(node.path_y)
- path_yaw = reversed(node.path_yaw)
- for (ix, iy, iyaw) in zip(path_x, path_y, path_yaw):
- path.append([ix, iy, iyaw])
- # path.append([node.x, node.y])
- goalind = node.parent
- path.append([self.start.x, self.start.y, self.start.yaw])
-
- path = np.array(path[::-1])
- return path
-
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def find_near_nodes(self, newNode):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- # r = self.expandDis * 5.0
- dlist = [(node.x - newNode.x) ** 2
- + (node.y - newNode.y) ** 2
- + (node.yaw - newNode.yaw) ** 2
- for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def rewire(self, newNode, nearinds):
-
- nnode = len(self.nodeList)
-
- for i in nearinds:
- nearNode = self.nodeList[i]
- tNode = self.steer(nearNode, nnode - 1)
-
- if tNode is None:
- continue
-
- obstacleOK = self.CollisionCheck(tNode, self.obstacleList)
- imporveCost = nearNode.cost > tNode.cost
-
- if obstacleOK and imporveCost:
- # print("rewire")
- self.nodeList[i] = tNode
-
- def DrawGraph(self, rnd=None): # pragma: no cover
- """
- Draw Graph
- """
- if rnd is not None:
- plt.plot(rnd.x, rnd.y, "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot(node.path_x, node.path_y, "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- reeds_shepp_path_planning.plot_arrow(
- self.start.x, self.start.y, self.start.yaw)
- reeds_shepp_path_planning.plot_arrow(
- self.end.x, self.end.y, self.end.yaw)
-
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd.x) ** 2
- + (node.y - rnd.y) ** 2
- + (node.yaw - rnd.yaw) ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
-
- return minind
-
- def CollisionCheck(self, node, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- for (ix, iy) in zip(node.path_x, node.path_y):
- dx = ox - ix
- dy = oy - iy
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
-
- return True # safe
-
- def CollisionCheckWithXY(self, x, y, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- for (ix, iy) in zip(x, y):
- dx = ox - ix
- dy = oy - iy
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
-
- return True # safe
-
-
-class Node():
- """
- RRT Node
- """
-
- def __init__(self, x, y, yaw):
- self.x = x
- self.y = y
- self.yaw = yaw
- self.path_x = []
- self.path_y = []
- self.path_yaw = []
- self.cost = 0.0
- self.parent = None
-
-def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), maxIter=500):
+def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), max_iter=100):
print("Start" + __file__)
# ====Search Path with RRT====
- obstacleList = [
+ obstacle_list = [
(5, 5, 1),
(4, 6, 1),
(4, 8, 1),
@@ -406,16 +167,19 @@ def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), maxIter=500):
start = [0.0, 0.0, np.deg2rad(0.0)]
goal = [gx, gy, gyaw]
- rrt = RRT(start, goal, randArea=[-2.0, 20.0],
- obstacleList=obstacleList, maxIter=maxIter)
- flag, x, y, yaw, v, t, a, d = rrt.Planning(animation=show_animation)
+ closed_loop_rrt_star = ClosedLoopRRTStar(start, goal,
+ obstacle_list,
+ [-2.0, 20.0],
+ max_iter=max_iter)
+ flag, x, y, yaw, v, t, a, d = closed_loop_rrt_star.planning(
+ animation=show_animation)
if not flag:
print("cannot find feasible path")
# Draw final path
if show_animation:
- rrt.DrawGraph()
+ closed_loop_rrt_star.draw_graph()
plt.plot(x, y, '-r')
plt.grid(True)
plt.pause(0.001)
diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py
index c90af1567d..982ebeca06 100644
--- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py
+++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py
@@ -5,10 +5,16 @@
author: Atsushi Sakai
"""
-import numpy as np
import math
+
import matplotlib.pyplot as plt
-import unicycle_model
+import numpy as np
+
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+
+from ClosedLoopRRTStar import unicycle_model
Kp = 2.0 # speed propotional gain
Lf = 0.5 # look-ahead distance
@@ -38,7 +44,7 @@ def pure_pursuit_control(state, cx, cy, pind):
if pind >= ind:
ind = pind
- # print(pind, ind)
+ # print(parent_index, ind)
if ind < len(cx):
tx = cx[ind]
ty = cy[ind]
@@ -66,17 +72,17 @@ def calc_target_index(state, cx, cy):
dx = [state.x - icx for icx in cx]
dy = [state.y - icy for icy in cy]
- d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)]
+ d = np.hypot(dx, dy)
mindis = min(d)
- ind = d.index(mindis)
+ ind = np.argmin(d)
L = 0.0
while Lf > L and (ind + 1) < len(cx):
dx = cx[ind + 1] - cx[ind]
- dy = cx[ind + 1] - cx[ind]
- L += math.sqrt(dx ** 2 + dy ** 2)
+ dy = cy[ind + 1] - cy[ind]
+ L += math.hypot(dx, dy)
ind += 1
# print(mindis)
@@ -119,7 +125,7 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal):
# check goal
dx = state.x - goal[0]
dy = state.y - goal[1]
- if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
+ if math.hypot(dx, dy) <= goal_dis:
find_goal = True
break
@@ -133,6 +139,9 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal):
if target_ind % 1 == 0 and animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(cx, cy, "-r", label="course")
plt.plot(x, y, "ob", label="trajectory")
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
@@ -153,12 +162,13 @@ def set_stop_point(target_speed, cx, cy, cyaw):
forward = True
d = []
+ is_back = False
# Set stop point
for i in range(len(cx) - 1):
dx = cx[i + 1] - cx[i]
dy = cy[i + 1] - cy[i]
- d.append(math.sqrt(dx ** 2.0 + dy ** 2.0))
+ d.append(math.hypot(dx, dy))
iyaw = cyaw[i]
move_direction = math.atan2(dy, dx)
is_back = abs(move_direction - iyaw) >= math.pi / 2.0
@@ -175,12 +185,12 @@ def set_stop_point(target_speed, cx, cy, cyaw):
speed_profile[i] = 0.0
forward = False
# plt.plot(cx[i], cy[i], "xb")
- # print(iyaw, move_direction, dx, dy)
+ # print(i_yaw, move_direction, dx, dy)
elif not is_back and not forward:
speed_profile[i] = 0.0
forward = True
# plt.plot(cx[i], cy[i], "xb")
- # print(iyaw, move_direction, dx, dy)
+ # print(i_yaw, move_direction, dx, dy)
speed_profile[0] = 0.0
if is_back:
speed_profile[-1] = -stop_speed
@@ -244,7 +254,7 @@ def main(): # pragma: no cover
yaw = [state.yaw]
v = [state.v]
t = [0.0]
- target_ind = calc_target_index(state, cx, cy)
+ target_ind, dis = calc_target_index(state, cx, cy)
while T >= time and lastIndex > target_ind:
ai = PIDControl(target_speed, state.v)
@@ -285,43 +295,6 @@ def main(): # pragma: no cover
plt.show()
-def main2(): # pragma: no cover
- import pandas as pd
- data = pd.read_csv("rrt_course.csv")
- cx = np.array(data["x"])
- cy = np.array(data["y"])
- cyaw = np.array(data["yaw"])
-
- target_speed = 10.0 / 3.6
-
- goal = [cx[-1], cy[-1]]
-
- cx, cy, cyaw = extend_path(cx, cy, cyaw)
-
- speed_profile = calc_speed_profile(cx, cy, cyaw, target_speed)
-
- t, x, y, yaw, v, a, d, flag = closed_loop_prediction(
- cx, cy, cyaw, speed_profile, goal)
-
- plt.subplots(1)
- plt.plot(cx, cy, ".r", label="course")
- plt.plot(x, y, "-b", label="trajectory")
- plt.plot(goal[0], goal[1], "xg", label="goal")
- plt.legend()
- plt.xlabel("x[m]")
- plt.ylabel("y[m]")
- plt.axis("equal")
- plt.grid(True)
-
- plt.subplots(1)
- plt.plot(t, [iv * 3.6 for iv in v], "-r")
- plt.xlabel("Time[s]")
- plt.ylabel("Speed[km/h]")
- plt.grid(True)
- plt.show()
-
-
if __name__ == '__main__': # pragma: no cover
print("Pure pursuit path tracking simulation start")
- # main()
- main2()
+ main()
diff --git a/PathPlanning/ClosedLoopRRTStar/unicycle_model.py b/PathPlanning/ClosedLoopRRTStar/unicycle_model.py
index 5a0fd17a4e..c05f76c84e 100644
--- a/PathPlanning/ClosedLoopRRTStar/unicycle_model.py
+++ b/PathPlanning/ClosedLoopRRTStar/unicycle_model.py
@@ -8,6 +8,7 @@
import math
import numpy as np
+from utils.angle import angle_mod
dt = 0.05 # [s]
L = 0.9 # [m]
@@ -39,7 +40,7 @@ def update(state, a, delta):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
if __name__ == '__main__': # pragma: no cover
diff --git a/PathPlanning/ClothoidPath/clothoid_path_planner.py b/PathPlanning/ClothoidPath/clothoid_path_planner.py
new file mode 100644
index 0000000000..5e5fc6e9a3
--- /dev/null
+++ b/PathPlanning/ClothoidPath/clothoid_path_planner.py
@@ -0,0 +1,192 @@
+"""
+Clothoid Path Planner
+Author: Daniel Ingram (daniel-s-ingram)
+ Atsushi Sakai (AtsushiSakai)
+Reference paper: Fast and accurate G1 fitting of clothoid curves
+https://www.researchgate.net/publication/237062806
+"""
+
+from collections import namedtuple
+import matplotlib.pyplot as plt
+import numpy as np
+import scipy.integrate as integrate
+from scipy.optimize import fsolve
+from math import atan2, cos, hypot, pi, sin
+from matplotlib import animation
+
+Point = namedtuple("Point", ["x", "y"])
+
+show_animation = True
+
+
+def generate_clothoid_paths(start_point, start_yaw_list,
+ goal_point, goal_yaw_list,
+ n_path_points):
+ """
+ Generate clothoid path list. This function generate multiple clothoid paths
+ from multiple orientations(yaw) at start points to multiple orientations
+ (yaw) at goal point.
+
+ :param start_point: Start point of the path
+ :param start_yaw_list: Orientation list at start point in radian
+ :param goal_point: Goal point of the path
+ :param goal_yaw_list: Orientation list at goal point in radian
+ :param n_path_points: number of path points
+ :return: clothoid path list
+ """
+ clothoids = []
+ for start_yaw in start_yaw_list:
+ for goal_yaw in goal_yaw_list:
+ clothoid = generate_clothoid_path(start_point, start_yaw,
+ goal_point, goal_yaw,
+ n_path_points)
+ clothoids.append(clothoid)
+ return clothoids
+
+
+def generate_clothoid_path(start_point, start_yaw,
+ goal_point, goal_yaw, n_path_points):
+ """
+ Generate a clothoid path list.
+
+ :param start_point: Start point of the path
+ :param start_yaw: Orientation at start point in radian
+ :param goal_point: Goal point of the path
+ :param goal_yaw: Orientation at goal point in radian
+ :param n_path_points: number of path points
+ :return: a clothoid path
+ """
+ dx = goal_point.x - start_point.x
+ dy = goal_point.y - start_point.y
+ r = hypot(dx, dy)
+
+ phi = atan2(dy, dx)
+ phi1 = normalize_angle(start_yaw - phi)
+ phi2 = normalize_angle(goal_yaw - phi)
+ delta = phi2 - phi1
+
+ try:
+ # Step1: Solve g function
+ A = solve_g_for_root(phi1, phi2, delta)
+
+ # Step2: Calculate path parameters
+ L = compute_path_length(r, phi1, delta, A)
+ curvature = compute_curvature(delta, A, L)
+ curvature_rate = compute_curvature_rate(A, L)
+ except Exception as e:
+ print(f"Failed to generate clothoid points: {e}")
+ return None
+
+ # Step3: Construct a path with Fresnel integral
+ points = []
+ for s in np.linspace(0, L, n_path_points):
+ try:
+ x = start_point.x + s * X(curvature_rate * s ** 2, curvature * s,
+ start_yaw)
+ y = start_point.y + s * Y(curvature_rate * s ** 2, curvature * s,
+ start_yaw)
+ points.append(Point(x, y))
+ except Exception as e:
+ print(f"Skipping failed clothoid point: {e}")
+
+ return points
+
+
+def X(a, b, c):
+ return integrate.quad(lambda t: cos((a/2)*t**2 + b*t + c), 0, 1)[0]
+
+
+def Y(a, b, c):
+ return integrate.quad(lambda t: sin((a/2)*t**2 + b*t + c), 0, 1)[0]
+
+
+def solve_g_for_root(theta1, theta2, delta):
+ initial_guess = 3*(theta1 + theta2)
+ return fsolve(lambda A: Y(2*A, delta - A, theta1), [initial_guess])
+
+
+def compute_path_length(r, theta1, delta, A):
+ return r / X(2*A, delta - A, theta1)
+
+
+def compute_curvature(delta, A, L):
+ return (delta - A) / L
+
+
+def compute_curvature_rate(A, L):
+ return 2 * A / (L**2)
+
+
+def normalize_angle(angle_rad):
+ return (angle_rad + pi) % (2 * pi) - pi
+
+
+def get_axes_limits(clothoids):
+ x_vals = [p.x for clothoid in clothoids for p in clothoid]
+ y_vals = [p.y for clothoid in clothoids for p in clothoid]
+
+ x_min = min(x_vals)
+ x_max = max(x_vals)
+ y_min = min(y_vals)
+ y_max = max(y_vals)
+
+ x_offset = 0.1*(x_max - x_min)
+ y_offset = 0.1*(y_max - y_min)
+
+ x_min = x_min - x_offset
+ x_max = x_max + x_offset
+ y_min = y_min - y_offset
+ y_max = y_max + y_offset
+
+ return x_min, x_max, y_min, y_max
+
+
+def draw_clothoids(start, goal, num_steps, clothoidal_paths,
+ save_animation=False):
+
+ fig = plt.figure(figsize=(10, 10))
+ x_min, x_max, y_min, y_max = get_axes_limits(clothoidal_paths)
+ axes = plt.axes(xlim=(x_min, x_max), ylim=(y_min, y_max))
+
+ axes.plot(start.x, start.y, 'ro')
+ axes.plot(goal.x, goal.y, 'ro')
+ lines = [axes.plot([], [], 'b-')[0] for _ in range(len(clothoidal_paths))]
+
+ def animate(i):
+ for line, clothoid_path in zip(lines, clothoidal_paths):
+ x = [p.x for p in clothoid_path[:i]]
+ y = [p.y for p in clothoid_path[:i]]
+ line.set_data(x, y)
+
+ return lines
+
+ anim = animation.FuncAnimation(
+ fig,
+ animate,
+ frames=num_steps,
+ interval=25,
+ blit=True
+ )
+ if save_animation:
+ anim.save('clothoid.gif', fps=30, writer="imagemagick")
+ plt.show()
+
+
+def main():
+ start_point = Point(0, 0)
+ start_orientation_list = [0.0]
+ goal_point = Point(10, 0)
+ goal_orientation_list = np.linspace(-pi, pi, 75)
+ num_path_points = 100
+ clothoid_paths = generate_clothoid_paths(
+ start_point, start_orientation_list,
+ goal_point, goal_orientation_list,
+ num_path_points)
+ if show_animation:
+ draw_clothoids(start_point, goal_point,
+ num_path_points, clothoid_paths,
+ save_animation=False)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/CubicSpline/Figure_1.png b/PathPlanning/CubicSpline/Figure_1.png
deleted file mode 100644
index 13eea2122d..0000000000
Binary files a/PathPlanning/CubicSpline/Figure_1.png and /dev/null differ
diff --git a/PathPlanning/CubicSpline/__init__.py b/PathPlanning/CubicSpline/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/CubicSpline/cubic_spline_planner.py b/PathPlanning/CubicSpline/cubic_spline_planner.py
index 071b117185..2391f67c39 100644
--- a/PathPlanning/CubicSpline/cubic_spline_planner.py
+++ b/PathPlanning/CubicSpline/cubic_spline_planner.py
@@ -9,87 +9,173 @@
import bisect
-class Spline:
+class CubicSpline1D:
"""
- Cubic Spline class
+ 1D Cubic Spline class
+
+ Parameters
+ ----------
+ x : list
+ x coordinates for data points. This x coordinates must be
+ sorted
+ in ascending order.
+ y : list
+ y coordinates for data points
+
+ Examples
+ --------
+ You can interpolate 1D data points.
+
+ >>> import numpy as np
+ >>> import matplotlib.pyplot as plt
+ >>> x = np.arange(5)
+ >>> y = [1.7, -6, 5, 6.5, 0.0]
+ >>> sp = CubicSpline1D(x, y)
+ >>> xi = np.linspace(0.0, 5.0)
+ >>> yi = [sp.calc_position(x) for x in xi]
+ >>> plt.plot(x, y, "xb", label="Data points")
+ >>> plt.plot(xi, yi , "r", label="Cubic spline interpolation")
+ >>> plt.grid(True)
+ >>> plt.legend()
+ >>> plt.show()
+
+ .. image:: cubic_spline_1d.png
+
"""
def __init__(self, x, y):
- self.b, self.c, self.d, self.w = [], [], [], []
+ h = np.diff(x)
+ if np.any(h < 0):
+ raise ValueError("x coordinates must be sorted in ascending order")
+
+ self.a, self.b, self.c, self.d = [], [], [], []
self.x = x
self.y = y
-
self.nx = len(x) # dimension of x
- h = np.diff(x)
- # calc coefficient c
+ # calc coefficient a
self.a = [iy for iy in y]
# calc coefficient c
A = self.__calc_A(h)
- B = self.__calc_B(h)
+ B = self.__calc_B(h, self.a)
self.c = np.linalg.solve(A, B)
- # print(self.c1)
# calc spline coefficient b and d
for i in range(self.nx - 1):
- self.d.append((self.c[i + 1] - self.c[i]) / (3.0 * h[i]))
- tb = (self.a[i + 1] - self.a[i]) / h[i] - h[i] * \
- (self.c[i + 1] + 2.0 * self.c[i]) / 3.0
- self.b.append(tb)
+ d = (self.c[i + 1] - self.c[i]) / (3.0 * h[i])
+ b = 1.0 / h[i] * (self.a[i + 1] - self.a[i]) \
+ - h[i] / 3.0 * (2.0 * self.c[i] + self.c[i + 1])
+ self.d.append(d)
+ self.b.append(b)
- def calc(self, t):
+ def calc_position(self, x):
"""
- Calc position
+ Calc `y` position for given `x`.
- if t is outside of the input x, return None
+ if `x` is outside the data point's `x` range, return None.
- """
+ Parameters
+ ----------
+ x : float
+ x position to calculate y.
- if t < self.x[0]:
+ Returns
+ -------
+ y : float
+ y position for given x.
+ """
+ if x < self.x[0]:
return None
- elif t > self.x[-1]:
+ elif x > self.x[-1]:
return None
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = self.a[i] + self.b[i] * dx + \
+ i = self.__search_index(x)
+ dx = x - self.x[i]
+ position = self.a[i] + self.b[i] * dx + \
self.c[i] * dx ** 2.0 + self.d[i] * dx ** 3.0
- return result
+ return position
- def calcd(self, t):
+ def calc_first_derivative(self, x):
"""
- Calc first derivative
+ Calc first derivative at given x.
+
+ if x is outside the input x, return None
+
+ Parameters
+ ----------
+ x : float
+ x position to calculate first derivative.
- if t is outside of the input x, return None
+ Returns
+ -------
+ dy : float
+ first derivative for given x.
"""
- if t < self.x[0]:
+ if x < self.x[0]:
return None
- elif t > self.x[-1]:
+ elif x > self.x[-1]:
return None
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = self.b[i] + 2.0 * self.c[i] * dx + 3.0 * self.d[i] * dx ** 2.0
- return result
+ i = self.__search_index(x)
+ dx = x - self.x[i]
+ dy = self.b[i] + 2.0 * self.c[i] * dx + 3.0 * self.d[i] * dx ** 2.0
+ return dy
- def calcdd(self, t):
+ def calc_second_derivative(self, x):
"""
- Calc second derivative
+ Calc second derivative at given x.
+
+ if x is outside the input x, return None
+
+ Parameters
+ ----------
+ x : float
+ x position to calculate second derivative.
+
+ Returns
+ -------
+ ddy : float
+ second derivative for given x.
"""
- if t < self.x[0]:
+ if x < self.x[0]:
return None
- elif t > self.x[-1]:
+ elif x > self.x[-1]:
return None
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = 2.0 * self.c[i] + 6.0 * self.d[i] * dx
- return result
+ i = self.__search_index(x)
+ dx = x - self.x[i]
+ ddy = 2.0 * self.c[i] + 6.0 * self.d[i] * dx
+ return ddy
+
+ def calc_third_derivative(self, x):
+ """
+ Calc third derivative at given x.
+
+ if x is outside the input x, return None
+
+ Parameters
+ ----------
+ x : float
+ x position to calculate third derivative.
+
+ Returns
+ -------
+ dddy : float
+ third derivative for given x.
+ """
+ if x < self.x[0]:
+ return None
+ elif x > self.x[-1]:
+ return None
+
+ i = self.__search_index(x)
+ dddy = 6.0 * self.d[i]
+ return dddy
def __search_index(self, x):
"""
@@ -112,36 +198,87 @@ def __calc_A(self, h):
A[0, 1] = 0.0
A[self.nx - 1, self.nx - 2] = 0.0
A[self.nx - 1, self.nx - 1] = 1.0
- # print(A)
return A
- def __calc_B(self, h):
+ def __calc_B(self, h, a):
"""
calc matrix B for spline coefficient c
"""
B = np.zeros(self.nx)
for i in range(self.nx - 2):
- B[i + 1] = 3.0 * (self.a[i + 2] - self.a[i + 1]) / \
- h[i + 1] - 3.0 * (self.a[i + 1] - self.a[i]) / h[i]
+ B[i + 1] = 3.0 * (a[i + 2] - a[i + 1]) / h[i + 1]\
+ - 3.0 * (a[i + 1] - a[i]) / h[i]
return B
-class Spline2D:
+class CubicSpline2D:
"""
- 2D Cubic Spline class
-
+ Cubic CubicSpline2D class
+
+ Parameters
+ ----------
+ x : list
+ x coordinates for data points.
+ y : list
+ y coordinates for data points.
+
+ Examples
+ --------
+ You can interpolate a 2D data points.
+
+ >>> import matplotlib.pyplot as plt
+ >>> x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0]
+ >>> y = [0.7, -6, 5, 6.5, 0.0, 5.0, -2.0]
+ >>> ds = 0.1 # [m] distance of each interpolated points
+ >>> sp = CubicSpline2D(x, y)
+ >>> s = np.arange(0, sp.s[-1], ds)
+ >>> rx, ry, ryaw, rk = [], [], [], []
+ >>> for i_s in s:
+ ... ix, iy = sp.calc_position(i_s)
+ ... rx.append(ix)
+ ... ry.append(iy)
+ ... ryaw.append(sp.calc_yaw(i_s))
+ ... rk.append(sp.calc_curvature(i_s))
+ >>> plt.subplots(1)
+ >>> plt.plot(x, y, "xb", label="Data points")
+ >>> plt.plot(rx, ry, "-r", label="Cubic spline path")
+ >>> plt.grid(True)
+ >>> plt.axis("equal")
+ >>> plt.xlabel("x[m]")
+ >>> plt.ylabel("y[m]")
+ >>> plt.legend()
+ >>> plt.show()
+
+ .. image:: cubic_spline_2d_path.png
+
+ >>> plt.subplots(1)
+ >>> plt.plot(s, [np.rad2deg(iyaw) for iyaw in ryaw], "-r", label="yaw")
+ >>> plt.grid(True)
+ >>> plt.legend()
+ >>> plt.xlabel("line length[m]")
+ >>> plt.ylabel("yaw angle[deg]")
+
+ .. image:: cubic_spline_2d_yaw.png
+
+ >>> plt.subplots(1)
+ >>> plt.plot(s, rk, "-r", label="curvature")
+ >>> plt.grid(True)
+ >>> plt.legend()
+ >>> plt.xlabel("line length[m]")
+ >>> plt.ylabel("curvature [1/m]")
+
+ .. image:: cubic_spline_2d_curvature.png
"""
def __init__(self, x, y):
self.s = self.__calc_s(x, y)
- self.sx = Spline(self.s, x)
- self.sy = Spline(self.s, y)
+ self.sx = CubicSpline1D(self.s, x)
+ self.sy = CubicSpline1D(self.s, y)
def __calc_s(self, x, y):
dx = np.diff(x)
dy = np.diff(y)
- self.ds = [math.sqrt(idx ** 2 + idy ** 2)
- for (idx, idy) in zip(dx, dy)]
+ self.ds = np.hypot(dx, dy)
s = [0]
s.extend(np.cumsum(self.ds))
return s
@@ -149,35 +286,97 @@ def __calc_s(self, x, y):
def calc_position(self, s):
"""
calc position
+
+ Parameters
+ ----------
+ s : float
+ distance from the start point. if `s` is outside the data point's
+ range, return None.
+
+ Returns
+ -------
+ x : float
+ x position for given s.
+ y : float
+ y position for given s.
"""
- x = self.sx.calc(s)
- y = self.sy.calc(s)
+ x = self.sx.calc_position(s)
+ y = self.sy.calc_position(s)
return x, y
def calc_curvature(self, s):
"""
calc curvature
+
+ Parameters
+ ----------
+ s : float
+ distance from the start point. if `s` is outside the data point's
+ range, return None.
+
+ Returns
+ -------
+ k : float
+ curvature for given s.
"""
- dx = self.sx.calcd(s)
- ddx = self.sx.calcdd(s)
- dy = self.sy.calcd(s)
- ddy = self.sy.calcdd(s)
+ dx = self.sx.calc_first_derivative(s)
+ ddx = self.sx.calc_second_derivative(s)
+ dy = self.sy.calc_first_derivative(s)
+ ddy = self.sy.calc_second_derivative(s)
k = (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2))
return k
+ def calc_curvature_rate(self, s):
+ """
+ calc curvature rate
+
+ Parameters
+ ----------
+ s : float
+ distance from the start point. if `s` is outside the data point's
+ range, return None.
+
+ Returns
+ -------
+ k : float
+ curvature rate for given s.
+ """
+ dx = self.sx.calc_first_derivative(s)
+ dy = self.sy.calc_first_derivative(s)
+ ddx = self.sx.calc_second_derivative(s)
+ ddy = self.sy.calc_second_derivative(s)
+ dddx = self.sx.calc_third_derivative(s)
+ dddy = self.sy.calc_third_derivative(s)
+ a = dx * ddy - dy * ddx
+ b = dx * dddy - dy * dddx
+ c = dx * ddx + dy * ddy
+ d = dx * dx + dy * dy
+ return (b * d - 3.0 * a * c) / (d * d * d)
+
def calc_yaw(self, s):
"""
calc yaw
+
+ Parameters
+ ----------
+ s : float
+ distance from the start point. if `s` is outside the data point's
+ range, return None.
+
+ Returns
+ -------
+ yaw : float
+ yaw angle (tangent vector) for given s.
"""
- dx = self.sx.calcd(s)
- dy = self.sy.calcd(s)
+ dx = self.sx.calc_first_derivative(s)
+ dy = self.sy.calc_first_derivative(s)
yaw = math.atan2(dy, dx)
return yaw
def calc_spline_course(x, y, ds=0.1):
- sp = Spline2D(x, y)
+ sp = CubicSpline2D(x, y)
s = list(np.arange(0, sp.s[-1], ds))
rx, ry, ryaw, rk = [], [], [], []
@@ -191,14 +390,30 @@ def calc_spline_course(x, y, ds=0.1):
return rx, ry, ryaw, rk, s
-def main():
- print("Spline 2D test")
+def main_1d():
+ print("CubicSpline1D test")
+ import matplotlib.pyplot as plt
+ x = np.arange(5)
+ y = [1.7, -6, 5, 6.5, 0.0]
+ sp = CubicSpline1D(x, y)
+ xi = np.linspace(0.0, 5.0)
+
+ plt.plot(x, y, "xb", label="Data points")
+ plt.plot(xi, [sp.calc_position(x) for x in xi], "r",
+ label="Cubic spline interpolation")
+ plt.grid(True)
+ plt.legend()
+ plt.show()
+
+
+def main_2d(): # pragma: no cover
+ print("CubicSpline1D 2D test")
import matplotlib.pyplot as plt
x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0]
y = [0.7, -6, 5, 6.5, 0.0, 5.0, -2.0]
- ds = 0.1 # [m] distance of each intepolated points
+ ds = 0.1 # [m] distance of each interpolated points
- sp = Spline2D(x, y)
+ sp = CubicSpline2D(x, y)
s = np.arange(0, sp.s[-1], ds)
rx, ry, ryaw, rk = [], [], [], []
@@ -210,8 +425,8 @@ def main():
rk.append(sp.calc_curvature(i_s))
plt.subplots(1)
- plt.plot(x, y, "xb", label="input")
- plt.plot(rx, ry, "-r", label="spline")
+ plt.plot(x, y, "xb", label="Data points")
+ plt.plot(rx, ry, "-r", label="Cubic spline path")
plt.grid(True)
plt.axis("equal")
plt.xlabel("x[m]")
@@ -236,4 +451,5 @@ def main():
if __name__ == '__main__':
- main()
+ # main_1d()
+ main_2d()
diff --git a/PathPlanning/CubicSpline/spline_continuity.py b/PathPlanning/CubicSpline/spline_continuity.py
new file mode 100644
index 0000000000..ea85b37f7c
--- /dev/null
+++ b/PathPlanning/CubicSpline/spline_continuity.py
@@ -0,0 +1,55 @@
+
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy import interpolate
+
+
+class Spline2D:
+
+ def __init__(self, x, y, kind="cubic"):
+ self.s = self.__calc_s(x, y)
+ self.sx = interpolate.interp1d(self.s, x, kind=kind)
+ self.sy = interpolate.interp1d(self.s, y, kind=kind)
+
+ def __calc_s(self, x, y):
+ self.ds = np.hypot(np.diff(x), np.diff(y))
+ s = [0.0]
+ s.extend(np.cumsum(self.ds))
+ return s
+
+ def calc_position(self, s):
+ x = self.sx(s)
+ y = self.sy(s)
+ return x, y
+
+
+def main():
+ x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0]
+ y = [0.7, -6, -5, -3.5, 0.0, 5.0, -2.0]
+ ds = 0.1 # [m] distance of each interpolated points
+
+ plt.subplots(1)
+ plt.plot(x, y, "xb", label="Data points")
+
+ for (kind, label) in [("linear", "C0 (Linear spline)"),
+ ("quadratic", "C0 & C1 (Quadratic spline)"),
+ ("cubic", "C0 & C1 & C2 (Cubic spline)")]:
+ rx, ry = [], []
+ sp = Spline2D(x, y, kind=kind)
+ s = np.arange(0, sp.s[-1], ds)
+ for i_s in s:
+ ix, iy = sp.calc_position(i_s)
+ rx.append(ix)
+ ry.append(iy)
+ plt.plot(rx, ry, "-", label=label)
+
+ plt.grid(True)
+ plt.axis("equal")
+ plt.xlabel("x[m]")
+ plt.ylabel("y[m]")
+ plt.legend()
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/DStar/dstar.py b/PathPlanning/DStar/dstar.py
new file mode 100644
index 0000000000..b62b939f54
--- /dev/null
+++ b/PathPlanning/DStar/dstar.py
@@ -0,0 +1,253 @@
+"""
+
+D* grid planning
+
+author: Nirnay Roy
+
+See Wikipedia article (https://en.wikipedia.org/wiki/D*)
+
+"""
+import math
+
+
+from sys import maxsize
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class State:
+
+ def __init__(self, x, y):
+ self.x = x
+ self.y = y
+ self.parent = None
+ self.state = "."
+ self.t = "new" # tag for state
+ self.h = 0
+ self.k = 0
+
+ def cost(self, state):
+ if self.state == "#" or state.state == "#":
+ return maxsize
+
+ return math.sqrt(math.pow((self.x - state.x), 2) +
+ math.pow((self.y - state.y), 2))
+
+ def set_state(self, state):
+ """
+ .: new
+ #: obstacle
+ e: oparent of current state
+ *: closed state
+ s: current state
+ """
+ if state not in ["s", ".", "#", "e", "*"]:
+ return
+ self.state = state
+
+
+class Map:
+
+ def __init__(self, row, col):
+ self.row = row
+ self.col = col
+ self.map = self.init_map()
+
+ def init_map(self):
+ map_list = []
+ for i in range(self.row):
+ tmp = []
+ for j in range(self.col):
+ tmp.append(State(i, j))
+ map_list.append(tmp)
+ return map_list
+
+ def get_neighbors(self, state):
+ state_list = []
+ for i in [-1, 0, 1]:
+ for j in [-1, 0, 1]:
+ if i == 0 and j == 0:
+ continue
+ if state.x + i < 0 or state.x + i >= self.row:
+ continue
+ if state.y + j < 0 or state.y + j >= self.col:
+ continue
+ state_list.append(self.map[state.x + i][state.y + j])
+ return state_list
+
+ def set_obstacle(self, point_list):
+ for x, y in point_list:
+ if x < 0 or x >= self.row or y < 0 or y >= self.col:
+ continue
+
+ self.map[x][y].set_state("#")
+
+
+class Dstar:
+ def __init__(self, maps):
+ self.map = maps
+ self.open_list = set()
+
+ def process_state(self):
+ x = self.min_state()
+
+ if x is None:
+ return -1
+
+ k_old = self.get_kmin()
+ self.remove(x)
+
+ if k_old < x.h:
+ for y in self.map.get_neighbors(x):
+ if y.h <= k_old and x.h > y.h + x.cost(y):
+ x.parent = y
+ x.h = y.h + x.cost(y)
+ if k_old == x.h:
+ for y in self.map.get_neighbors(x):
+ if y.t == "new" or y.parent == x and y.h != x.h + x.cost(y) \
+ or y.parent != x and y.h > x.h + x.cost(y):
+ y.parent = x
+ self.insert(y, x.h + x.cost(y))
+ else:
+ for y in self.map.get_neighbors(x):
+ if y.t == "new" or y.parent == x and y.h != x.h + x.cost(y):
+ y.parent = x
+ self.insert(y, x.h + x.cost(y))
+ else:
+ if y.parent != x and y.h > x.h + x.cost(y):
+ self.insert(x, x.h)
+ else:
+ if y.parent != x and x.h > y.h + x.cost(y) \
+ and y.t == "close" and y.h > k_old:
+ self.insert(y, y.h)
+ return self.get_kmin()
+
+ def min_state(self):
+ if not self.open_list:
+ return None
+ min_state = min(self.open_list, key=lambda x: x.k)
+ return min_state
+
+ def get_kmin(self):
+ if not self.open_list:
+ return -1
+ k_min = min([x.k for x in self.open_list])
+ return k_min
+
+ def insert(self, state, h_new):
+ if state.t == "new":
+ state.k = h_new
+ elif state.t == "open":
+ state.k = min(state.k, h_new)
+ elif state.t == "close":
+ state.k = min(state.h, h_new)
+ state.h = h_new
+ state.t = "open"
+ self.open_list.add(state)
+
+ def remove(self, state):
+ if state.t == "open":
+ state.t = "close"
+ self.open_list.remove(state)
+
+ def modify_cost(self, x):
+ if x.t == "close":
+ self.insert(x, x.parent.h + x.cost(x.parent))
+
+ def run(self, start, end):
+
+ rx = []
+ ry = []
+
+ self.insert(end, 0.0)
+
+ while True:
+ self.process_state()
+ if start.t == "close":
+ break
+
+ start.set_state("s")
+ s = start
+ s = s.parent
+ s.set_state("e")
+ tmp = start
+
+ AddNewObstacle(self.map) # add new obstacle after the first search finished
+
+ while tmp != end:
+ tmp.set_state("*")
+ rx.append(tmp.x)
+ ry.append(tmp.y)
+ if show_animation:
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
+ if tmp.parent.state == "#":
+ self.modify(tmp)
+ continue
+ tmp = tmp.parent
+ tmp.set_state("e")
+
+ return rx, ry
+
+ def modify(self, state):
+ self.modify_cost(state)
+ while True:
+ k_min = self.process_state()
+ if k_min >= state.h:
+ break
+
+def AddNewObstacle(map:Map):
+ ox, oy = [], []
+ for i in range(5, 21):
+ ox.append(i)
+ oy.append(40)
+ map.set_obstacle([(i, j) for i, j in zip(ox, oy)])
+ if show_animation:
+ plt.pause(0.001)
+ plt.plot(ox, oy, ".g")
+
+def main():
+ m = Map(100, 100)
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10)
+ for i in range(-10, 60):
+ ox.append(60)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60)
+ for i in range(-10, 61):
+ ox.append(-10)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40)
+ oy.append(60 - i)
+ m.set_obstacle([(i, j) for i, j in zip(ox, oy)])
+
+ start = [10, 10]
+ goal = [50, 50]
+ if show_animation:
+ plt.plot(ox, oy, ".k")
+ plt.plot(start[0], start[1], "og")
+ plt.plot(goal[0], goal[1], "xb")
+ plt.axis("equal")
+
+ start = m.map[start[0]][start[1]]
+ end = m.map[goal[0]][goal[1]]
+ dstar = Dstar(m)
+ rx, ry = dstar.run(start, end)
+
+ if show_animation:
+ plt.plot(rx, ry, "-r")
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/DStarLite/d_star_lite.py b/PathPlanning/DStarLite/d_star_lite.py
new file mode 100644
index 0000000000..1a44d84fa5
--- /dev/null
+++ b/PathPlanning/DStarLite/d_star_lite.py
@@ -0,0 +1,405 @@
+"""
+D* Lite grid planning
+author: vss2sn (28676655+vss2sn@users.noreply.github.com)
+Link to papers:
+D* Lite (Link: http://idm-lab.org/bib/abstracts/papers/aaai02b.pdf)
+Improved Fast Replanning for Robot Navigation in Unknown Terrain
+(Link: http://www.cs.cmu.edu/~maxim/files/dlite_icra02.pdf)
+Implemented maintaining similarity with the pseudocode for understanding.
+Code can be significantly optimized by using a priority queue for U, etc.
+Avoiding additional imports based on repository philosophy.
+"""
+import math
+import matplotlib.pyplot as plt
+import random
+import numpy as np
+
+show_animation = True
+pause_time = 0.001
+p_create_random_obstacle = 0
+
+
+class Node:
+ def __init__(self, x: int = 0, y: int = 0, cost: float = 0.0):
+ self.x = x
+ self.y = y
+ self.cost = cost
+
+
+def add_coordinates(node1: Node, node2: Node):
+ new_node = Node()
+ new_node.x = node1.x + node2.x
+ new_node.y = node1.y + node2.y
+ new_node.cost = node1.cost + node2.cost
+ return new_node
+
+
+def compare_coordinates(node1: Node, node2: Node):
+ return node1.x == node2.x and node1.y == node2.y
+
+
+class DStarLite:
+
+ # Please adjust the heuristic function (h) if you change the list of
+ # possible motions
+ motions = [
+ Node(1, 0, 1),
+ Node(0, 1, 1),
+ Node(-1, 0, 1),
+ Node(0, -1, 1),
+ Node(1, 1, math.sqrt(2)),
+ Node(1, -1, math.sqrt(2)),
+ Node(-1, 1, math.sqrt(2)),
+ Node(-1, -1, math.sqrt(2))
+ ]
+
+ def __init__(self, ox: list, oy: list):
+ # Ensure that within the algorithm implementation all node coordinates
+ # are indices in the grid and extend
+ # from 0 to abs(_max - _min)
+ self.x_min_world = int(min(ox))
+ self.y_min_world = int(min(oy))
+ self.x_max = int(abs(max(ox) - self.x_min_world))
+ self.y_max = int(abs(max(oy) - self.y_min_world))
+ self.obstacles = [Node(x - self.x_min_world, y - self.y_min_world)
+ for x, y in zip(ox, oy)]
+ self.obstacles_xy = {(obstacle.x, obstacle.y) for obstacle in self.obstacles}
+ self.start = Node(0, 0)
+ self.goal = Node(0, 0)
+ self.U = list() # type: ignore
+ self.km = 0.0
+ self.kold = 0.0
+ self.rhs = self.create_grid(float("inf"))
+ self.g = self.create_grid(float("inf"))
+ self.detected_obstacles_xy: set[tuple[int, int]] = set()
+ self.xy = np.empty((0, 2))
+ if show_animation:
+ self.detected_obstacles_for_plotting_x = list() # type: ignore
+ self.detected_obstacles_for_plotting_y = list() # type: ignore
+ self.initialized = False
+
+ def create_grid(self, val: float):
+ return np.full((self.x_max, self.y_max), val)
+
+ def is_obstacle(self, node: Node):
+ is_in_obstacles = (node.x, node.y) in self.obstacles_xy
+ is_in_detected_obstacles = (node.x, node.y) in self.detected_obstacles_xy
+ return is_in_obstacles or is_in_detected_obstacles
+
+ def c(self, node1: Node, node2: Node):
+ if self.is_obstacle(node2):
+ # Attempting to move from or to an obstacle
+ return math.inf
+ new_node = Node(node1.x-node2.x, node1.y-node2.y)
+ detected_motion = list(filter(lambda motion:
+ compare_coordinates(motion, new_node),
+ self.motions))
+ return detected_motion[0].cost
+
+ def h(self, s: Node):
+ # Cannot use the 2nd euclidean norm as this might sometimes generate
+ # heuristics that overestimate the cost, making them inadmissible,
+ # due to rounding errors etc (when combined with calculate_key)
+ # To be admissible heuristic should
+ # never overestimate the cost of a move
+ # hence not using the line below
+ # return math.hypot(self.start.x - s.x, self.start.y - s.y)
+
+ # Below is the same as 1; modify if you modify the cost of each move in
+ # motion
+ # return max(abs(self.start.x - s.x), abs(self.start.y - s.y))
+ return 1
+
+ def calculate_key(self, s: Node):
+ return (min(self.g[s.x][s.y], self.rhs[s.x][s.y]) + self.h(s)
+ + self.km, min(self.g[s.x][s.y], self.rhs[s.x][s.y]))
+
+ def is_valid(self, node: Node):
+ if 0 <= node.x < self.x_max and 0 <= node.y < self.y_max:
+ return True
+ return False
+
+ def get_neighbours(self, u: Node):
+ return [add_coordinates(u, motion) for motion in self.motions
+ if self.is_valid(add_coordinates(u, motion))]
+
+ def pred(self, u: Node):
+ # Grid, so each vertex is connected to the ones around it
+ return self.get_neighbours(u)
+
+ def succ(self, u: Node):
+ # Grid, so each vertex is connected to the ones around it
+ return self.get_neighbours(u)
+
+ def initialize(self, start: Node, goal: Node):
+ self.start.x = start.x - self.x_min_world
+ self.start.y = start.y - self.y_min_world
+ self.goal.x = goal.x - self.x_min_world
+ self.goal.y = goal.y - self.y_min_world
+ if not self.initialized:
+ self.initialized = True
+ print('Initializing')
+ self.U = list() # Would normally be a priority queue
+ self.km = 0.0
+ self.rhs = self.create_grid(math.inf)
+ self.g = self.create_grid(math.inf)
+ self.rhs[self.goal.x][self.goal.y] = 0
+ self.U.append((self.goal, self.calculate_key(self.goal)))
+ self.detected_obstacles_xy = set()
+
+ def update_vertex(self, u: Node):
+ if not compare_coordinates(u, self.goal):
+ self.rhs[u.x][u.y] = min([self.c(u, sprime) +
+ self.g[sprime.x][sprime.y]
+ for sprime in self.succ(u)])
+ if any([compare_coordinates(u, node) for node, key in self.U]):
+ self.U = [(node, key) for node, key in self.U
+ if not compare_coordinates(node, u)]
+ self.U.sort(key=lambda x: x[1])
+ if self.g[u.x][u.y] != self.rhs[u.x][u.y]:
+ self.U.append((u, self.calculate_key(u)))
+ self.U.sort(key=lambda x: x[1])
+
+ def compare_keys(self, key_pair1: tuple[float, float],
+ key_pair2: tuple[float, float]):
+ return key_pair1[0] < key_pair2[0] or \
+ (key_pair1[0] == key_pair2[0] and key_pair1[1] < key_pair2[1])
+
+ def compute_shortest_path(self):
+ self.U.sort(key=lambda x: x[1])
+ has_elements = len(self.U) > 0
+ start_key_not_updated = self.compare_keys(
+ self.U[0][1], self.calculate_key(self.start)
+ )
+ rhs_not_equal_to_g = self.rhs[self.start.x][self.start.y] != \
+ self.g[self.start.x][self.start.y]
+ while has_elements and start_key_not_updated or rhs_not_equal_to_g:
+ self.kold = self.U[0][1]
+ u = self.U[0][0]
+ self.U.pop(0)
+ if self.compare_keys(self.kold, self.calculate_key(u)):
+ self.U.append((u, self.calculate_key(u)))
+ self.U.sort(key=lambda x: x[1])
+ elif (self.g[u.x, u.y] > self.rhs[u.x, u.y]).any():
+ self.g[u.x, u.y] = self.rhs[u.x, u.y]
+ for s in self.pred(u):
+ self.update_vertex(s)
+ else:
+ self.g[u.x, u.y] = math.inf
+ for s in self.pred(u) + [u]:
+ self.update_vertex(s)
+ self.U.sort(key=lambda x: x[1])
+ start_key_not_updated = self.compare_keys(
+ self.U[0][1], self.calculate_key(self.start)
+ )
+ rhs_not_equal_to_g = self.rhs[self.start.x][self.start.y] != \
+ self.g[self.start.x][self.start.y]
+
+ def detect_changes(self):
+ changed_vertices = list()
+ if len(self.spoofed_obstacles) > 0:
+ for spoofed_obstacle in self.spoofed_obstacles[0]:
+ if compare_coordinates(spoofed_obstacle, self.start) or \
+ compare_coordinates(spoofed_obstacle, self.goal):
+ continue
+ changed_vertices.append(spoofed_obstacle)
+ self.detected_obstacles_xy.add((spoofed_obstacle.x, spoofed_obstacle.y))
+ if show_animation:
+ self.detected_obstacles_for_plotting_x.append(
+ spoofed_obstacle.x + self.x_min_world)
+ self.detected_obstacles_for_plotting_y.append(
+ spoofed_obstacle.y + self.y_min_world)
+ plt.plot(self.detected_obstacles_for_plotting_x,
+ self.detected_obstacles_for_plotting_y, ".k")
+ plt.pause(pause_time)
+ self.spoofed_obstacles.pop(0)
+
+ # Allows random generation of obstacles
+ random.seed()
+ if random.random() > 1 - p_create_random_obstacle:
+ x = random.randint(0, self.x_max - 1)
+ y = random.randint(0, self.y_max - 1)
+ new_obs = Node(x, y)
+ if compare_coordinates(new_obs, self.start) or \
+ compare_coordinates(new_obs, self.goal):
+ return changed_vertices
+ changed_vertices.append(Node(x, y))
+ self.detected_obstacles_xy.add((x, y))
+ if show_animation:
+ self.detected_obstacles_for_plotting_x.append(x +
+ self.x_min_world)
+ self.detected_obstacles_for_plotting_y.append(y +
+ self.y_min_world)
+ plt.plot(self.detected_obstacles_for_plotting_x,
+ self.detected_obstacles_for_plotting_y, ".k")
+ plt.pause(pause_time)
+ return changed_vertices
+
+ def compute_current_path(self):
+ path = list()
+ current_point = Node(self.start.x, self.start.y)
+ while not compare_coordinates(current_point, self.goal):
+ path.append(current_point)
+ current_point = min(self.succ(current_point),
+ key=lambda sprime:
+ self.c(current_point, sprime) +
+ self.g[sprime.x][sprime.y])
+ path.append(self.goal)
+ return path
+
+ def compare_paths(self, path1: list, path2: list):
+ if len(path1) != len(path2):
+ return False
+ for node1, node2 in zip(path1, path2):
+ if not compare_coordinates(node1, node2):
+ return False
+ return True
+
+ def display_path(self, path: list, colour: str, alpha: float = 1.0):
+ px = [(node.x + self.x_min_world) for node in path]
+ py = [(node.y + self.y_min_world) for node in path]
+ drawing = plt.plot(px, py, colour, alpha=alpha)
+ plt.pause(pause_time)
+ return drawing
+
+ def main(self, start: Node, goal: Node,
+ spoofed_ox: list, spoofed_oy: list):
+ self.spoofed_obstacles = [[Node(x - self.x_min_world,
+ y - self.y_min_world)
+ for x, y in zip(rowx, rowy)]
+ for rowx, rowy in zip(spoofed_ox, spoofed_oy)
+ ]
+ pathx = []
+ pathy = []
+ self.initialize(start, goal)
+ last = self.start
+ self.compute_shortest_path()
+ pathx.append(self.start.x + self.x_min_world)
+ pathy.append(self.start.y + self.y_min_world)
+
+ if show_animation:
+ current_path = self.compute_current_path()
+ previous_path = current_path.copy()
+ previous_path_image = self.display_path(previous_path, ".c",
+ alpha=0.3)
+ current_path_image = self.display_path(current_path, ".c")
+
+ while not compare_coordinates(self.goal, self.start):
+ if self.g[self.start.x][self.start.y] == math.inf:
+ print("No path possible")
+ return False, pathx, pathy
+ self.start = min(self.succ(self.start),
+ key=lambda sprime:
+ self.c(self.start, sprime) +
+ self.g[sprime.x][sprime.y])
+ pathx.append(self.start.x + self.x_min_world)
+ pathy.append(self.start.y + self.y_min_world)
+ if show_animation:
+ current_path.pop(0)
+ plt.plot(pathx, pathy, "-r")
+ plt.pause(pause_time)
+ changed_vertices = self.detect_changes()
+ if len(changed_vertices) != 0:
+ print("New obstacle detected")
+ self.km += self.h(last)
+ last = self.start
+ for u in changed_vertices:
+ if compare_coordinates(u, self.start):
+ continue
+ self.rhs[u.x][u.y] = math.inf
+ self.g[u.x][u.y] = math.inf
+ self.update_vertex(u)
+ self.compute_shortest_path()
+
+ if show_animation:
+ new_path = self.compute_current_path()
+ if not self.compare_paths(current_path, new_path):
+ current_path_image[0].remove()
+ previous_path_image[0].remove()
+ previous_path = current_path.copy()
+ current_path = new_path.copy()
+ previous_path_image = self.display_path(previous_path,
+ ".c",
+ alpha=0.3)
+ current_path_image = self.display_path(current_path,
+ ".c")
+ plt.pause(pause_time)
+ print("Path found")
+ return True, pathx, pathy
+
+
+def main():
+
+ # start and goal position
+ sx = 10 # [m]
+ sy = 10 # [m]
+ gx = 50 # [m]
+ gy = 50 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation:
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "xb")
+ plt.grid(True)
+ plt.axis("equal")
+ label_column = ['Start', 'Goal', 'Path taken',
+ 'Current computed path', 'Previous computed path',
+ 'Obstacles']
+ columns = [plt.plot([], [], symbol, color=colour, alpha=alpha)[0]
+ for symbol, colour, alpha in [['o', 'g', 1],
+ ['x', 'b', 1],
+ ['-', 'r', 1],
+ ['.', 'c', 1],
+ ['.', 'c', 0.3],
+ ['.', 'k', 1]]]
+ plt.legend(columns, label_column, bbox_to_anchor=(1, 1), title="Key:",
+ fontsize="xx-small")
+ plt.plot()
+ plt.pause(pause_time)
+
+ # Obstacles discovered at time = row
+ # time = 1, obstacles discovered at (0, 2), (9, 2), (4, 0)
+ # time = 2, obstacles discovered at (0, 1), (7, 7)
+ # ...
+ # when the spoofed obstacles are:
+ # spoofed_ox = [[0, 9, 4], [0, 7], [], [], [], [], [], [5]]
+ # spoofed_oy = [[2, 2, 0], [1, 7], [], [], [], [], [], [4]]
+
+ # Reroute
+ # spoofed_ox = [[], [], [], [], [], [], [], [40 for _ in range(10, 21)]]
+ # spoofed_oy = [[], [], [], [], [], [], [], [i for i in range(10, 21)]]
+
+ # Obstacles that demostrate large rerouting
+ spoofed_ox = [[], [], [],
+ [i for i in range(0, 21)] + [0 for _ in range(0, 20)]]
+ spoofed_oy = [[], [], [],
+ [20 for _ in range(0, 21)] + [i for i in range(0, 20)]]
+
+ dstarlite = DStarLite(ox, oy)
+ dstarlite.main(Node(x=sx, y=sy), Node(x=gx, y=gy),
+ spoofed_ox=spoofed_ox, spoofed_oy=spoofed_oy)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py
new file mode 100644
index 0000000000..6922b8cbad
--- /dev/null
+++ b/PathPlanning/DepthFirstSearch/depth_first_search.py
@@ -0,0 +1,255 @@
+"""
+
+Depth-First grid planning
+
+author: Erwin Lejeune (@spida_rwin)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/Depth-first_search)
+
+"""
+
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class DepthFirstSearchPlanner:
+
+ def __init__(self, ox, oy, reso, rr):
+ """
+ Initialize grid map for Depth-First planning
+
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ self.reso = reso
+ self.rr = rr
+ self.calc_obstacle_map(ox, oy)
+ self.motion = self.get_motion_model()
+
+ class Node:
+ def __init__(self, x, y, cost, parent_index, parent):
+ self.x = x # index of grid
+ self.y = y # index of grid
+ self.cost = cost
+ self.parent_index = parent_index
+ self.parent = parent
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
+
+ def planning(self, sx, sy, gx, gy):
+ """
+ Depth First search
+
+ input:
+ s_x: start x position [m]
+ s_y: start y position [m]
+ gx: goal x position [m]
+ gy: goal y position [m]
+
+ output:
+ rx: x position list of the final path
+ ry: y position list of the final path
+ """
+
+ nstart = self.Node(self.calc_xyindex(sx, self.minx),
+ self.calc_xyindex(sy, self.miny), 0.0, -1, None)
+ ngoal = self.Node(self.calc_xyindex(gx, self.minx),
+ self.calc_xyindex(gy, self.miny), 0.0, -1, None)
+
+ open_set, closed_set = dict(), dict()
+ open_set[self.calc_grid_index(nstart)] = nstart
+
+ while True:
+ if len(open_set) == 0:
+ print("Open set is empty..")
+ break
+
+ current = open_set.pop(list(open_set.keys())[-1])
+ c_id = self.calc_grid_index(current)
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(self.calc_grid_position(current.x, self.minx),
+ self.calc_grid_position(current.y, self.miny), "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event:
+ [exit(0) if event.key == 'escape'
+ else None])
+ plt.pause(0.01)
+
+ if current.x == ngoal.x and current.y == ngoal.y:
+ print("Find goal")
+ ngoal.parent_index = current.parent_index
+ ngoal.cost = current.cost
+ break
+
+ # expand_grid search grid based on motion model
+ for i, _ in enumerate(self.motion):
+ node = self.Node(current.x + self.motion[i][0],
+ current.y + self.motion[i][1],
+ current.cost + self.motion[i][2], c_id, None)
+ n_id = self.calc_grid_index(node)
+
+ # If the node is not safe, do nothing
+ if not self.verify_node(node):
+ continue
+
+ if n_id not in closed_set:
+ open_set[n_id] = node
+ closed_set[n_id] = node
+ node.parent = current
+
+ rx, ry = self.calc_final_path(ngoal, closed_set)
+ return rx, ry
+
+ def calc_final_path(self, ngoal, closedset):
+ # generate final course
+ rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [
+ self.calc_grid_position(ngoal.y, self.miny)]
+ n = closedset[ngoal.parent_index]
+ while n is not None:
+ rx.append(self.calc_grid_position(n.x, self.minx))
+ ry.append(self.calc_grid_position(n.y, self.miny))
+ n = n.parent
+
+ return rx, ry
+
+ def calc_grid_position(self, index, minp):
+ """
+ calc grid position
+
+ :param index:
+ :param minp:
+ :return:
+ """
+ pos = index * self.reso + minp
+ return pos
+
+ def calc_xyindex(self, position, min_pos):
+ return round((position - min_pos) / self.reso)
+
+ def calc_grid_index(self, node):
+ return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
+
+ def verify_node(self, node):
+ px = self.calc_grid_position(node.x, self.minx)
+ py = self.calc_grid_position(node.y, self.miny)
+
+ if px < self.minx:
+ return False
+ elif py < self.miny:
+ return False
+ elif px >= self.maxx:
+ return False
+ elif py >= self.maxy:
+ return False
+
+ # collision check
+ if self.obmap[node.x][node.y]:
+ return False
+
+ return True
+
+ def calc_obstacle_map(self, ox, oy):
+
+ self.minx = round(min(ox))
+ self.miny = round(min(oy))
+ self.maxx = round(max(ox))
+ self.maxy = round(max(oy))
+ print("min_x:", self.minx)
+ print("min_y:", self.miny)
+ print("max_x:", self.maxx)
+ print("max_y:", self.maxy)
+
+ self.xwidth = round((self.maxx - self.minx) / self.reso)
+ self.ywidth = round((self.maxy - self.miny) / self.reso)
+ print("x_width:", self.xwidth)
+ print("y_width:", self.ywidth)
+
+ # obstacle map generation
+ self.obmap = [[False for _ in range(self.ywidth)]
+ for _ in range(self.xwidth)]
+ for ix in range(self.xwidth):
+ x = self.calc_grid_position(ix, self.minx)
+ for iy in range(self.ywidth):
+ y = self.calc_grid_position(iy, self.miny)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.rr:
+ self.obmap[ix][iy] = True
+ break
+
+ @staticmethod
+ def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx = 10.0 # [m]
+ sy = 10.0 # [m]
+ gx = 50.0 # [m]
+ gy = 50.0 # [m]
+ grid_size = 2.0 # [m]
+ robot_radius = 1.0 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation: # pragma: no cover
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "xb")
+ plt.grid(True)
+ plt.axis("equal")
+
+ dfs = DepthFirstSearchPlanner(ox, oy, grid_size, robot_radius)
+ rx, ry = dfs.planning(sx, sy, gx, gy)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py
index bb73ed501a..f5a4703910 100644
--- a/PathPlanning/Dijkstra/dijkstra.py
+++ b/PathPlanning/Dijkstra/dijkstra.py
@@ -11,40 +11,50 @@
show_animation = True
-class Dijkstra:
- def __init__(self, ox, oy, reso, rr):
+class DijkstraPlanner:
+
+ def __init__(self, ox, oy, resolution, robot_radius):
"""
Initialize map for a star planning
ox: x position list of Obstacles [m]
oy: y position list of Obstacles [m]
- reso: grid resolution [m]
+ resolution: grid resolution [m]
rr: robot radius[m]
"""
- self.reso = reso
- self.rr = rr
+ self.min_x = None
+ self.min_y = None
+ self.max_x = None
+ self.max_y = None
+ self.x_width = None
+ self.y_width = None
+ self.obstacle_map = None
+
+ self.resolution = resolution
+ self.robot_radius = robot_radius
self.calc_obstacle_map(ox, oy)
self.motion = self.get_motion_model()
class Node:
- def __init__(self, x, y, cost, pind):
+ def __init__(self, x, y, cost, parent_index):
self.x = x # index of grid
self.y = y # index of grid
self.cost = cost
- self.pind = pind
+ self.parent_index = parent_index # index of previous Node
def __str__(self):
- return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
def planning(self, sx, sy, gx, gy):
"""
dijkstra path search
input:
- sx: start x position [m]
- sy: start y position [m]
+ s_x: start x position [m]
+ s_y: start y position [m]
gx: goal x position [m]
gx: goal x position [m]
@@ -53,137 +63,137 @@ def planning(self, sx, sy, gx, gy):
ry: y position list of the final path
"""
- nstart = self.Node(self.calc_xyindex(sx, self.minx),
- self.calc_xyindex(sy, self.miny), 0.0, -1)
- ngoal = self.Node(self.calc_xyindex(gx, self.minx),
- self.calc_xyindex(gy, self.miny), 0.0, -1)
+ start_node = self.Node(self.calc_xy_index(sx, self.min_x),
+ self.calc_xy_index(sy, self.min_y), 0.0, -1)
+ goal_node = self.Node(self.calc_xy_index(gx, self.min_x),
+ self.calc_xy_index(gy, self.min_y), 0.0, -1)
- openset, closedset = dict(), dict()
- openset[self.calc_index(nstart)] = nstart
+ open_set, closed_set = dict(), dict()
+ open_set[self.calc_index(start_node)] = start_node
- while 1:
- c_id = min(openset, key=lambda o: openset[o].cost)
- current = openset[c_id]
+ while True:
+ c_id = min(open_set, key=lambda o: open_set[o].cost)
+ current = open_set[c_id]
# show graph
if show_animation: # pragma: no cover
- plt.plot(self.calc_position(current.x, self.minx),
- self.calc_position(current.y, self.miny), "xc")
- if len(closedset.keys()) % 10 == 0:
+ plt.plot(self.calc_position(current.x, self.min_x),
+ self.calc_position(current.y, self.min_y), "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if len(closed_set.keys()) % 10 == 0:
plt.pause(0.001)
- if current.x == ngoal.x and current.y == ngoal.y:
+ if current.x == goal_node.x and current.y == goal_node.y:
print("Find goal")
- ngoal.pind = current.pind
- ngoal.cost = current.cost
+ goal_node.parent_index = current.parent_index
+ goal_node.cost = current.cost
break
# Remove the item from the open set
- del openset[c_id]
+ del open_set[c_id]
# Add it to the closed set
- closedset[c_id] = current
+ closed_set[c_id] = current
# expand search grid based on motion model
- for i, _ in enumerate(self.motion):
- node = self.Node(current.x + self.motion[i][0],
- current.y + self.motion[i][1],
- current.cost + self.motion[i][2], c_id)
+ for move_x, move_y, move_cost in self.motion:
+ node = self.Node(current.x + move_x,
+ current.y + move_y,
+ current.cost + move_cost, c_id)
n_id = self.calc_index(node)
- if n_id in closedset:
+ if n_id in closed_set:
continue
if not self.verify_node(node):
continue
- if n_id not in openset:
- openset[n_id] = node # Discover a new node
+ if n_id not in open_set:
+ open_set[n_id] = node # Discover a new node
else:
- if openset[n_id].cost >= node.cost:
+ if open_set[n_id].cost >= node.cost:
# This path is the best until now. record it!
- openset[n_id] = node
+ open_set[n_id] = node
- rx, ry = self.calc_final_path(ngoal, closedset)
+ rx, ry = self.calc_final_path(goal_node, closed_set)
return rx, ry
- def calc_final_path(self, ngoal, closedset):
+ def calc_final_path(self, goal_node, closed_set):
# generate final course
- rx, ry = [self.calc_position(ngoal.x, self.minx)], [
- self.calc_position(ngoal.y, self.miny)]
- pind = ngoal.pind
- while pind != -1:
- n = closedset[pind]
- rx.append(self.calc_position(n.x, self.minx))
- ry.append(self.calc_position(n.y, self.miny))
- pind = n.pind
+ rx, ry = [self.calc_position(goal_node.x, self.min_x)], [
+ self.calc_position(goal_node.y, self.min_y)]
+ parent_index = goal_node.parent_index
+ while parent_index != -1:
+ n = closed_set[parent_index]
+ rx.append(self.calc_position(n.x, self.min_x))
+ ry.append(self.calc_position(n.y, self.min_y))
+ parent_index = n.parent_index
return rx, ry
- def calc_heuristic(self, n1, n2):
- w = 1.0 # weight of heuristic
- d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2)
- return d
-
def calc_position(self, index, minp):
- pos = index*self.reso+minp
+ pos = index * self.resolution + minp
return pos
- def calc_xyindex(self, position, minp):
- return round((position - minp)/self.reso)
+ def calc_xy_index(self, position, minp):
+ return round((position - minp) / self.resolution)
def calc_index(self, node):
- return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
+ return (node.y - self.min_y) * self.x_width + (node.x - self.min_x)
def verify_node(self, node):
- px = self.calc_position(node.x, self.minx)
- py = self.calc_position(node.y, self.miny)
+ px = self.calc_position(node.x, self.min_x)
+ py = self.calc_position(node.y, self.min_y)
- if px < self.minx:
+ if px < self.min_x:
return False
- elif py < self.miny:
+ if py < self.min_y:
return False
- elif px >= self.maxx:
+ if px >= self.max_x:
return False
- elif py >= self.maxy:
+ if py >= self.max_y:
return False
- if self.obmap[node.x][node.y]:
+ if self.obstacle_map[node.x][node.y]:
return False
return True
def calc_obstacle_map(self, ox, oy):
- self.minx = round(min(ox))
- self.miny = round(min(oy))
- self.maxx = round(max(ox))
- self.maxy = round(max(oy))
- print("minx:", self.minx)
- print("miny:", self.miny)
- print("maxx:", self.maxx)
- print("maxy:", self.maxy)
+ self.min_x = round(min(ox))
+ self.min_y = round(min(oy))
+ self.max_x = round(max(ox))
+ self.max_y = round(max(oy))
+ print("min_x:", self.min_x)
+ print("min_y:", self.min_y)
+ print("max_x:", self.max_x)
+ print("max_y:", self.max_y)
- self.xwidth = round((self.maxx - self.minx)/self.reso)
- self.ywidth = round((self.maxy - self.miny)/self.reso)
- print("xwidth:", self.xwidth)
- print("ywidth:", self.ywidth)
+ self.x_width = round((self.max_x - self.min_x) / self.resolution)
+ self.y_width = round((self.max_y - self.min_y) / self.resolution)
+ print("x_width:", self.x_width)
+ print("y_width:", self.y_width)
# obstacle map generation
- self.obmap = [[False for i in range(self.ywidth)]
- for i in range(self.xwidth)]
- for ix in range(self.xwidth):
- x = self.calc_position(ix, self.minx)
- for iy in range(self.ywidth):
- y = self.calc_position(iy, self.miny)
+ self.obstacle_map = [[False for _ in range(self.y_width)]
+ for _ in range(self.x_width)]
+ for ix in range(self.x_width):
+ x = self.calc_position(ix, self.min_x)
+ for iy in range(self.y_width):
+ y = self.calc_position(iy, self.min_y)
for iox, ioy in zip(ox, oy):
- d = math.sqrt((iox - x)**2 + (ioy - y)**2)
- if d <= self.rr:
- self.obmap[ix][iy] = True
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.robot_radius:
+ self.obstacle_map[ix][iy] = True
break
- def get_motion_model(self):
+ @staticmethod
+ def get_motion_model():
# dx, dy, cost
motion = [[1, 0, 1],
[0, 1, 1],
@@ -211,20 +221,20 @@ def main():
# set obstacle positions
ox, oy = [], []
for i in range(-10, 60):
- ox.append(i)
+ ox.append(float(i))
oy.append(-10.0)
for i in range(-10, 60):
ox.append(60.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(-10, 61):
- ox.append(i)
+ ox.append(float(i))
oy.append(60.0)
for i in range(-10, 61):
ox.append(-10.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(-10, 40):
ox.append(20.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(0, 40):
ox.append(40.0)
oy.append(60.0 - i)
@@ -236,11 +246,12 @@ def main():
plt.grid(True)
plt.axis("equal")
- dijkstra = Dijkstra(ox, oy, grid_size, robot_radius)
+ dijkstra = DijkstraPlanner(ox, oy, grid_size, robot_radius)
rx, ry = dijkstra.planning(sx, sy, gx, gy)
if show_animation: # pragma: no cover
plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
plt.show()
diff --git a/PathPlanning/DubinsPath/dubins_path_planner.py b/PathPlanning/DubinsPath/dubins_path_planner.py
new file mode 100644
index 0000000000..a7e8a100cc
--- /dev/null
+++ b/PathPlanning/DubinsPath/dubins_path_planner.py
@@ -0,0 +1,317 @@
+"""
+
+Dubins path planner sample code
+
+author Atsushi Sakai(@Atsushi_twi)
+
+"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
+from math import sin, cos, atan2, sqrt, acos, pi, hypot
+import numpy as np
+from utils.angle import angle_mod, rot_mat_2d
+
+show_animation = True
+
+
+def plan_dubins_path(s_x, s_y, s_yaw, g_x, g_y, g_yaw, curvature,
+ step_size=0.1, selected_types=None):
+ """
+ Plan dubins path
+
+ Parameters
+ ----------
+ s_x : float
+ x position of the start point [m]
+ s_y : float
+ y position of the start point [m]
+ s_yaw : float
+ yaw angle of the start point [rad]
+ g_x : float
+ x position of the goal point [m]
+ g_y : float
+ y position of the end point [m]
+ g_yaw : float
+ yaw angle of the end point [rad]
+ curvature : float
+ curvature for curve [1/m]
+ step_size : float (optional)
+ step size between two path points [m]. Default is 0.1
+ selected_types : a list of string or None
+ selected path planning types. If None, all types are used for
+ path planning, and minimum path length result is returned.
+ You can select used path plannings types by a string list.
+ e.g.: ["RSL", "RSR"]
+
+ Returns
+ -------
+ x_list: array
+ x positions of the path
+ y_list: array
+ y positions of the path
+ yaw_list: array
+ yaw angles of the path
+ modes: array
+ mode list of the path
+ lengths: array
+ arrow_length list of the path segments.
+
+ Examples
+ --------
+ You can generate a dubins path.
+
+ >>> start_x = 1.0 # [m]
+ >>> start_y = 1.0 # [m]
+ >>> start_yaw = np.deg2rad(45.0) # [rad]
+ >>> end_x = -3.0 # [m]
+ >>> end_y = -3.0 # [m]
+ >>> end_yaw = np.deg2rad(-45.0) # [rad]
+ >>> curvature = 1.0
+ >>> path_x, path_y, path_yaw, mode, _ = plan_dubins_path(
+ start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature)
+ >>> plt.plot(path_x, path_y, label="final course " + "".join(mode))
+ >>> plot_arrow(start_x, start_y, start_yaw)
+ >>> plot_arrow(end_x, end_y, end_yaw)
+ >>> plt.legend()
+ >>> plt.grid(True)
+ >>> plt.axis("equal")
+ >>> plt.show()
+
+ .. image:: dubins_path.jpg
+ """
+ if selected_types is None:
+ planning_funcs = _PATH_TYPE_MAP.values()
+ else:
+ planning_funcs = [_PATH_TYPE_MAP[ptype] for ptype in selected_types]
+
+ # calculate local goal x, y, yaw
+ l_rot = rot_mat_2d(s_yaw)
+ le_xy = np.stack([g_x - s_x, g_y - s_y]).T @ l_rot
+ local_goal_x = le_xy[0]
+ local_goal_y = le_xy[1]
+ local_goal_yaw = g_yaw - s_yaw
+
+ lp_x, lp_y, lp_yaw, modes, lengths = _dubins_path_planning_from_origin(
+ local_goal_x, local_goal_y, local_goal_yaw, curvature, step_size,
+ planning_funcs)
+
+ # Convert a local coordinate path to the global coordinate
+ rot = rot_mat_2d(-s_yaw)
+ converted_xy = np.stack([lp_x, lp_y]).T @ rot
+ x_list = converted_xy[:, 0] + s_x
+ y_list = converted_xy[:, 1] + s_y
+ yaw_list = angle_mod(np.array(lp_yaw) + s_yaw)
+
+ return x_list, y_list, yaw_list, modes, lengths
+
+
+def _mod2pi(theta):
+ return angle_mod(theta, zero_2_2pi=True)
+
+
+def _calc_trig_funcs(alpha, beta):
+ sin_a = sin(alpha)
+ sin_b = sin(beta)
+ cos_a = cos(alpha)
+ cos_b = cos(beta)
+ cos_ab = cos(alpha - beta)
+ return sin_a, sin_b, cos_a, cos_b, cos_ab
+
+
+def _LSL(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ mode = ["L", "S", "L"]
+ p_squared = 2 + d ** 2 - (2 * cos_ab) + (2 * d * (sin_a - sin_b))
+ if p_squared < 0: # invalid configuration
+ return None, None, None, mode
+ tmp = atan2((cos_b - cos_a), d + sin_a - sin_b)
+ d1 = _mod2pi(-alpha + tmp)
+ d2 = sqrt(p_squared)
+ d3 = _mod2pi(beta - tmp)
+ return d1, d2, d3, mode
+
+
+def _RSR(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ mode = ["R", "S", "R"]
+ p_squared = 2 + d ** 2 - (2 * cos_ab) + (2 * d * (sin_b - sin_a))
+ if p_squared < 0:
+ return None, None, None, mode
+ tmp = atan2((cos_a - cos_b), d - sin_a + sin_b)
+ d1 = _mod2pi(alpha - tmp)
+ d2 = sqrt(p_squared)
+ d3 = _mod2pi(-beta + tmp)
+ return d1, d2, d3, mode
+
+
+def _LSR(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ p_squared = -2 + d ** 2 + (2 * cos_ab) + (2 * d * (sin_a + sin_b))
+ mode = ["L", "S", "R"]
+ if p_squared < 0:
+ return None, None, None, mode
+ d1 = sqrt(p_squared)
+ tmp = atan2((-cos_a - cos_b), (d + sin_a + sin_b)) - atan2(-2.0, d1)
+ d2 = _mod2pi(-alpha + tmp)
+ d3 = _mod2pi(-_mod2pi(beta) + tmp)
+ return d2, d1, d3, mode
+
+
+def _RSL(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ p_squared = d ** 2 - 2 + (2 * cos_ab) - (2 * d * (sin_a + sin_b))
+ mode = ["R", "S", "L"]
+ if p_squared < 0:
+ return None, None, None, mode
+ d1 = sqrt(p_squared)
+ tmp = atan2((cos_a + cos_b), (d - sin_a - sin_b)) - atan2(2.0, d1)
+ d2 = _mod2pi(alpha - tmp)
+ d3 = _mod2pi(beta - tmp)
+ return d2, d1, d3, mode
+
+
+def _RLR(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ mode = ["R", "L", "R"]
+ tmp = (6.0 - d ** 2 + 2.0 * cos_ab + 2.0 * d * (sin_a - sin_b)) / 8.0
+ if abs(tmp) > 1.0:
+ return None, None, None, mode
+ d2 = _mod2pi(2 * pi - acos(tmp))
+ d1 = _mod2pi(alpha - atan2(cos_a - cos_b, d - sin_a + sin_b) + d2 / 2.0)
+ d3 = _mod2pi(alpha - beta - d1 + d2)
+ return d1, d2, d3, mode
+
+
+def _LRL(alpha, beta, d):
+ sin_a, sin_b, cos_a, cos_b, cos_ab = _calc_trig_funcs(alpha, beta)
+ mode = ["L", "R", "L"]
+ tmp = (6.0 - d ** 2 + 2.0 * cos_ab + 2.0 * d * (- sin_a + sin_b)) / 8.0
+ if abs(tmp) > 1.0:
+ return None, None, None, mode
+ d2 = _mod2pi(2 * pi - acos(tmp))
+ d1 = _mod2pi(-alpha - atan2(cos_a - cos_b, d + sin_a - sin_b) + d2 / 2.0)
+ d3 = _mod2pi(_mod2pi(beta) - alpha - d1 + _mod2pi(d2))
+ return d1, d2, d3, mode
+
+
+_PATH_TYPE_MAP = {"LSL": _LSL, "RSR": _RSR, "LSR": _LSR, "RSL": _RSL,
+ "RLR": _RLR, "LRL": _LRL, }
+
+
+def _dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature,
+ step_size, planning_funcs):
+ dx = end_x
+ dy = end_y
+ d = hypot(dx, dy) * curvature
+
+ theta = _mod2pi(atan2(dy, dx))
+ alpha = _mod2pi(-theta)
+ beta = _mod2pi(end_yaw - theta)
+
+ best_cost = float("inf")
+ b_d1, b_d2, b_d3, b_mode = None, None, None, None
+
+ for planner in planning_funcs:
+ d1, d2, d3, mode = planner(alpha, beta, d)
+ if d1 is None:
+ continue
+
+ cost = (abs(d1) + abs(d2) + abs(d3))
+ if best_cost > cost: # Select minimum length one.
+ b_d1, b_d2, b_d3, b_mode, best_cost = d1, d2, d3, mode, cost
+
+ lengths = [b_d1, b_d2, b_d3]
+ x_list, y_list, yaw_list = _generate_local_course(lengths, b_mode,
+ curvature, step_size)
+
+ lengths = [length / curvature for length in lengths]
+
+ return x_list, y_list, yaw_list, b_mode, lengths
+
+
+def _interpolate(length, mode, max_curvature, origin_x, origin_y,
+ origin_yaw, path_x, path_y, path_yaw):
+ if mode == "S":
+ path_x.append(origin_x + length / max_curvature * cos(origin_yaw))
+ path_y.append(origin_y + length / max_curvature * sin(origin_yaw))
+ path_yaw.append(origin_yaw)
+ else: # curve
+ ldx = sin(length) / max_curvature
+ ldy = 0.0
+ if mode == "L": # left turn
+ ldy = (1.0 - cos(length)) / max_curvature
+ elif mode == "R": # right turn
+ ldy = (1.0 - cos(length)) / -max_curvature
+ gdx = cos(-origin_yaw) * ldx + sin(-origin_yaw) * ldy
+ gdy = -sin(-origin_yaw) * ldx + cos(-origin_yaw) * ldy
+ path_x.append(origin_x + gdx)
+ path_y.append(origin_y + gdy)
+
+ if mode == "L": # left turn
+ path_yaw.append(origin_yaw + length)
+ elif mode == "R": # right turn
+ path_yaw.append(origin_yaw - length)
+
+ return path_x, path_y, path_yaw
+
+
+def _generate_local_course(lengths, modes, max_curvature, step_size):
+ p_x, p_y, p_yaw = [0.0], [0.0], [0.0]
+
+ for (mode, length) in zip(modes, lengths):
+ if length == 0.0:
+ continue
+
+ # set origin state
+ origin_x, origin_y, origin_yaw = p_x[-1], p_y[-1], p_yaw[-1]
+
+ current_length = step_size
+ while abs(current_length + step_size) <= abs(length):
+ p_x, p_y, p_yaw = _interpolate(current_length, mode, max_curvature,
+ origin_x, origin_y, origin_yaw,
+ p_x, p_y, p_yaw)
+ current_length += step_size
+
+ p_x, p_y, p_yaw = _interpolate(length, mode, max_curvature, origin_x,
+ origin_y, origin_yaw, p_x, p_y, p_yaw)
+
+ return p_x, p_y, p_yaw
+
+
+def main():
+ print("Dubins path planner sample start!!")
+ import matplotlib.pyplot as plt
+ from utils.plot import plot_arrow
+
+ start_x = 1.0 # [m]
+ start_y = 1.0 # [m]
+ start_yaw = np.deg2rad(45.0) # [rad]
+
+ end_x = -3.0 # [m]
+ end_y = -3.0 # [m]
+ end_yaw = np.deg2rad(-45.0) # [rad]
+
+ curvature = 1.0
+
+ path_x, path_y, path_yaw, mode, lengths = plan_dubins_path(start_x,
+ start_y,
+ start_yaw,
+ end_x,
+ end_y,
+ end_yaw,
+ curvature)
+
+ if show_animation:
+ plt.plot(path_x, path_y, label="".join(mode))
+ plot_arrow(start_x, start_y, start_yaw)
+ plot_arrow(end_x, end_y, end_yaw)
+ plt.legend()
+ plt.grid(True)
+ plt.axis("equal")
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py
deleted file mode 100644
index dc7485ad9a..0000000000
--- a/PathPlanning/DubinsPath/dubins_path_planning.py
+++ /dev/null
@@ -1,338 +0,0 @@
-"""
-
-Dubins path planner sample code
-
-author Atsushi Sakai(@Atsushi_twi)
-
-"""
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-
-show_animation = True
-
-
-def mod2pi(theta):
- return theta - 2.0 * math.pi * math.floor(theta / 2.0 / math.pi)
-
-
-def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
-
-
-def LSL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- tmp0 = d + sa - sb
-
- mode = ["L", "S", "L"]
- p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sa - sb))
- if p_squared < 0:
- return None, None, None, mode
- tmp1 = math.atan2((cb - ca), tmp0)
- t = mod2pi(-alpha + tmp1)
- p = math.sqrt(p_squared)
- q = mod2pi(beta - tmp1)
- # print(np.rad2deg(t), p, np.rad2deg(q))
-
- return t, p, q, mode
-
-
-def RSR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- tmp0 = d - sa + sb
- mode = ["R", "S", "R"]
- p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sb - sa))
- if p_squared < 0:
- return None, None, None, mode
- tmp1 = math.atan2((ca - cb), tmp0)
- t = mod2pi(alpha - tmp1)
- p = math.sqrt(p_squared)
- q = mod2pi(-beta + tmp1)
-
- return t, p, q, mode
-
-
-def LSR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- p_squared = -2 + (d * d) + (2 * c_ab) + (2 * d * (sa + sb))
- mode = ["L", "S", "R"]
- if p_squared < 0:
- return None, None, None, mode
- p = math.sqrt(p_squared)
- tmp2 = math.atan2((-ca - cb), (d + sa + sb)) - math.atan2(-2.0, p)
- t = mod2pi(-alpha + tmp2)
- q = mod2pi(-mod2pi(beta) + tmp2)
-
- return t, p, q, mode
-
-
-def RSL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- p_squared = (d * d) - 2 + (2 * c_ab) - (2 * d * (sa + sb))
- mode = ["R", "S", "L"]
- if p_squared < 0:
- return None, None, None, mode
- p = math.sqrt(p_squared)
- tmp2 = math.atan2((ca + cb), (d - sa - sb)) - math.atan2(2.0, p)
- t = mod2pi(alpha - tmp2)
- q = mod2pi(beta - tmp2)
-
- return t, p, q, mode
-
-
-def RLR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- mode = ["R", "L", "R"]
- tmp_rlr = (6.0 - d * d + 2.0 * c_ab + 2.0 * d * (sa - sb)) / 8.0
- if abs(tmp_rlr) > 1.0:
- return None, None, None, mode
-
- p = mod2pi(2 * math.pi - math.acos(tmp_rlr))
- t = mod2pi(alpha - math.atan2(ca - cb, d - sa + sb) + mod2pi(p / 2.0))
- q = mod2pi(alpha - beta - t + mod2pi(p))
- return t, p, q, mode
-
-
-def LRL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- mode = ["L", "R", "L"]
- tmp_lrl = (6.0 - d * d + 2.0 * c_ab + 2.0 * d * (- sa + sb)) / 8.0
- if abs(tmp_lrl) > 1:
- return None, None, None, mode
- p = mod2pi(2 * math.pi - math.acos(tmp_lrl))
- t = mod2pi(-alpha - math.atan2(ca - cb, d + sa - sb) + p / 2.0)
- q = mod2pi(mod2pi(beta) - alpha - t + mod2pi(p))
-
- return t, p, q, mode
-
-
-def dubins_path_planning_from_origin(ex, ey, eyaw, c):
- # nomalize
- dx = ex
- dy = ey
- D = math.sqrt(dx ** 2.0 + dy ** 2.0)
- d = D * c
- # print(dx, dy, D, d)
-
- theta = mod2pi(math.atan2(dy, dx))
- alpha = mod2pi(- theta)
- beta = mod2pi(eyaw - theta)
- # print(theta, alpha, beta, d)
-
- planners = [LSL, RSR, LSR, RSL, RLR, LRL]
-
- bcost = float("inf")
- bt, bp, bq, bmode = None, None, None, None
-
- for planner in planners:
- t, p, q, mode = planner(alpha, beta, d)
- if t is None:
- continue
-
- cost = (abs(t) + abs(p) + abs(q))
- if bcost > cost:
- bt, bp, bq, bmode = t, p, q, mode
- bcost = cost
-
- # print(bmode)
- px, py, pyaw = generate_course([bt, bp, bq], bmode, c)
-
- return px, py, pyaw, bmode, bcost
-
-
-def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c):
- """
- Dubins path plannner
-
- input:
- sx x position of start point [m]
- sy y position of start point [m]
- syaw yaw angle of start point [rad]
- ex x position of end point [m]
- ey y position of end point [m]
- eyaw yaw angle of end point [rad]
- c curvature [1/m]
-
- output:
- px
- py
- pyaw
- mode
-
- """
-
- ex = ex - sx
- ey = ey - sy
-
- lex = math.cos(syaw) * ex + math.sin(syaw) * ey
- ley = - math.sin(syaw) * ex + math.cos(syaw) * ey
- leyaw = eyaw - syaw
-
- lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin(
- lex, ley, leyaw, c)
-
- px = [math.cos(-syaw) * x + math.sin(-syaw)
- * y + sx for x, y in zip(lpx, lpy)]
- py = [- math.sin(-syaw) * x + math.cos(-syaw)
- * y + sy for x, y in zip(lpx, lpy)]
- pyaw = [pi_2_pi(iyaw + syaw) for iyaw in lpyaw]
-
- return px, py, pyaw, mode, clen
-
-
-def generate_course(length, mode, c):
-
- px = [0.0]
- py = [0.0]
- pyaw = [0.0]
-
- for m, l in zip(mode, length):
- pd = 0.0
- if m == "S":
- d = 1.0 * c
- else: # turning couse
- d = np.deg2rad(3.0)
-
- while pd < abs(l - d):
- # print(pd, l)
- px.append(px[-1] + d / c * math.cos(pyaw[-1]))
- py.append(py[-1] + d / c * math.sin(pyaw[-1]))
-
- if m == "L": # left turn
- pyaw.append(pyaw[-1] + d)
- elif m == "S": # Straight
- pyaw.append(pyaw[-1])
- elif m == "R": # right turn
- pyaw.append(pyaw[-1] - d)
- pd += d
-
- d = l - pd
- px.append(px[-1] + d / c * math.cos(pyaw[-1]))
- py.append(py[-1] + d / c * math.sin(pyaw[-1]))
-
- if m == "L": # left turn
- pyaw.append(pyaw[-1] + d)
- elif m == "S": # Straight
- pyaw.append(pyaw[-1])
- elif m == "R": # right turn
- pyaw.append(pyaw[-1] - d)
- pd += d
-
- return px, py, pyaw
-
-
-def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover
- """
- Plot arrow
- """
-
- if not isinstance(x, float):
- for (ix, iy, iyaw) in zip(x, y, yaw):
- plot_arrow(ix, iy, iyaw)
- else:
- plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw),
- fc=fc, ec=ec, head_width=width, head_length=width)
- plt.plot(x, y)
-
-
-def main():
- print("Dubins path planner sample start!!")
-
- start_x = 1.0 # [m]
- start_y = 1.0 # [m]
- start_yaw = np.deg2rad(45.0) # [rad]
-
- end_x = -3.0 # [m]
- end_y = -3.0 # [m]
- end_yaw = np.deg2rad(-45.0) # [rad]
-
- curvature = 1.0
-
- px, py, pyaw, mode, clen = dubins_path_planning(start_x, start_y, start_yaw,
- end_x, end_y, end_yaw, curvature)
-
- if show_animation:
- plt.plot(px, py, label="final course " + "".join(mode))
-
- # plotting
- plot_arrow(start_x, start_y, start_yaw)
- plot_arrow(end_x, end_y, end_yaw)
-
- # for (ix, iy, iyaw) in zip(px, py, pyaw):
- # plot_arrow(ix, iy, iyaw, fc="b")
-
- plt.legend()
- plt.grid(True)
- plt.axis("equal")
- plt.show()
-
-
-def test():
-
- NTEST = 5
-
- for i in range(NTEST):
- start_x = (np.random.rand() - 0.5) * 10.0 # [m]
- start_y = (np.random.rand() - 0.5) * 10.0 # [m]
- start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
-
- end_x = (np.random.rand() - 0.5) * 10.0 # [m]
- end_y = (np.random.rand() - 0.5) * 10.0 # [m]
- end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
-
- curvature = 1.0 / (np.random.rand() * 5.0)
-
- px, py, pyaw, mode, clen = dubins_path_planning(
- start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature)
-
- if show_animation:
- plt.cla()
- plt.plot(px, py, label="final course " + str(mode))
-
- # plotting
- plot_arrow(start_x, start_y, start_yaw)
- plot_arrow(end_x, end_y, end_yaw)
-
- plt.legend()
- plt.grid(True)
- plt.axis("equal")
- plt.xlim(-10, 10)
- plt.ylim(-10, 10)
- plt.pause(1.0)
-
- print("Test done")
-
-
-if __name__ == '__main__':
- test()
- main()
diff --git a/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py
new file mode 100644
index 0000000000..9ccd18b7c2
--- /dev/null
+++ b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py
@@ -0,0 +1,260 @@
+"""
+Author: Jonathan Schwartz (github.com/SchwartzCode)
+
+This code provides a simple implementation of Dynamic Movement
+Primitives, which is an approach to learning curves by modelling
+them as a weighted sum of gaussian distributions. This approach
+can be used to dampen noise in a curve, and can also be used to
+stretch a curve by adjusting its start and end points.
+
+More information on Dynamic Movement Primitives available at:
+https://arxiv.org/abs/2102.03861
+https://www.frontiersin.org/journals/computational-neuroscience/articles/10.3389/fncom.2013.00138/full
+
+"""
+
+
+from matplotlib import pyplot as plt
+import numpy as np
+
+
+class DMP:
+
+ def __init__(self, training_data, data_period, K=156.25, B=25):
+ """
+ Arguments:
+ training_data - input data of form [N, dim]
+ data_period - amount of time training data covers
+ K and B - spring and damper constants to define
+ DMP behavior
+ """
+
+ self.K = K # virtual spring constant
+ self.B = B # virtual damper coefficient
+
+ self.timesteps = training_data.shape[0]
+ self.dt = data_period / self.timesteps
+
+ self.weights = None # weights used to generate DMP trajectories
+
+ self.T_orig = data_period
+
+ self.training_data = training_data
+ self.find_basis_functions_weights(training_data, data_period)
+
+ def find_basis_functions_weights(self, training_data, data_period,
+ num_weights=10):
+ """
+ Arguments:
+ data [(steps x spacial dim) np array] - data to replicate with DMP
+ data_period [float] - time duration of data
+ """
+
+ if not isinstance(training_data, np.ndarray):
+ print("Warning: you should input training data as an np.ndarray")
+ elif training_data.shape[0] < training_data.shape[1]:
+ print("Warning: you probably need to transpose your training data")
+
+ dt = data_period / len(training_data)
+
+ init_state = training_data[0]
+ goal_state = training_data[-1]
+
+ # means (C) and std devs (H) of gaussian basis functions
+ C = np.linspace(0, 1, num_weights)
+ H = (0.65*(1./(num_weights-1))**2)
+
+ for dim, _ in enumerate(training_data[0]):
+
+ dimension_data = training_data[:, dim]
+
+ q0 = init_state[dim]
+ g = goal_state[dim]
+
+ q = q0
+ qd_last = 0
+
+ phi_vals = []
+ f_vals = []
+
+ for i, _ in enumerate(dimension_data):
+ if i + 1 == len(dimension_data):
+ qd = 0
+ else:
+ qd = (dimension_data[i+1] - dimension_data[i]) / dt
+
+ phi = [np.exp(-0.5 * ((i * dt / data_period) - c)**2 / H)
+ for c in C]
+ phi = phi/np.sum(phi)
+
+ qdd = (qd - qd_last)/dt
+
+ f = (qdd * data_period**2 - self.K * (g - q) + self.B * qd
+ * data_period) / (g - q0)
+
+ phi_vals.append(phi)
+ f_vals.append(f)
+
+ qd_last = qd
+ q += qd * dt
+
+ phi_vals = np.asarray(phi_vals)
+ f_vals = np.asarray(f_vals)
+
+ w = np.linalg.lstsq(phi_vals, f_vals, rcond=None)
+
+ if self.weights is None:
+ self.weights = np.asarray(w[0])
+ else:
+ self.weights = np.vstack([self.weights, w[0]])
+
+ def recreate_trajectory(self, init_state, goal_state, T):
+ """
+ init_state - initial state/position
+ goal_state - goal state/position
+ T - amount of time to travel q0 -> g
+ """
+
+ nrBasis = len(self.weights[0]) # number of gaussian basis functions
+
+ # means (C) and std devs (H) of gaussian basis functions
+ C = np.linspace(0, 1, nrBasis)
+ H = (0.65*(1./(nrBasis-1))**2)
+
+ # initialize virtual system
+ time = 0
+
+ q = init_state
+ dimensions = self.weights.shape[0]
+ qd = np.zeros(dimensions)
+
+ positions = np.array([])
+ for k in range(self.timesteps):
+ time = time + self.dt
+
+ qdd = np.zeros(dimensions)
+
+ for dim in range(dimensions):
+
+ if time <= T:
+ phi = [np.exp(-0.5 * ((time / T) - c)**2 / H) for c in C]
+ phi = phi / np.sum(phi)
+ f = np.dot(phi, self.weights[dim])
+ else:
+ f = 0
+
+ # simulate dynamics
+ qdd[dim] = (self.K*(goal_state[dim] - q[dim])/T**2
+ - self.B*qd[dim]/T
+ + (goal_state[dim] - init_state[dim])*f/T**2)
+
+ qd = qd + qdd * self.dt
+ q = q + qd * self.dt
+
+ if positions.size == 0:
+ positions = q
+ else:
+ positions = np.vstack([positions, q])
+
+ t = np.arange(0, self.timesteps * self.dt, self.dt)
+ return t, positions
+
+ @staticmethod
+ def dist_between(p1, p2):
+ return np.linalg.norm(p1 - p2)
+
+ def view_trajectory(self, path, title=None, demo=False):
+
+ path = np.asarray(path)
+
+ plt.cla()
+ plt.plot(self.training_data[:, 0], self.training_data[:, 1],
+ label="Training Data")
+ plt.plot(path[:, 0], path[:, 1],
+ linewidth=2, label="DMP Approximation")
+
+ plt.xlabel("X Position")
+ plt.ylabel("Y Position")
+ plt.legend()
+
+ if title is not None:
+ plt.title(title)
+
+ if demo:
+ plt.xlim([-0.5, 5])
+ plt.ylim([-2, 2])
+ plt.draw()
+ plt.pause(0.02)
+ else:
+ plt.show()
+
+ def show_DMP_purpose(self):
+ """
+ This function conveys the purpose of DMPs:
+ to capture a trajectory and be able to stretch
+ and squeeze it in terms of start and stop position
+ or time
+ """
+
+ q0_orig = self.training_data[0]
+ g_orig = self.training_data[-1]
+ T_orig = self.T_orig
+
+ data_range = (np.amax(self.training_data[:, 0])
+ - np.amin(self.training_data[:, 0])) / 4
+
+ q0_right = q0_orig + np.array([data_range, 0])
+ q0_up = q0_orig + np.array([0, data_range/2])
+ g_left = g_orig - np.array([data_range, 0])
+ g_down = g_orig - np.array([0, data_range/2])
+
+ q0_vals = np.vstack([np.linspace(q0_orig, q0_right, 20),
+ np.linspace(q0_orig, q0_up, 20)])
+ g_vals = np.vstack([np.linspace(g_orig, g_left, 20),
+ np.linspace(g_orig, g_down, 20)])
+ T_vals = np.linspace(T_orig, 2*T_orig, 20)
+
+ for new_q0_value in q0_vals:
+ plot_title = (f"Initial Position = [{round(new_q0_value[0], 2)},"
+ f" {round(new_q0_value[1], 2)}]")
+
+ _, path = self.recreate_trajectory(new_q0_value, g_orig, T_orig)
+ self.view_trajectory(path, title=plot_title, demo=True)
+
+ for new_g_value in g_vals:
+ plot_title = (f"Goal Position = [{round(new_g_value[0], 2)},"
+ f" {round(new_g_value[1], 2)}]")
+
+ _, path = self.recreate_trajectory(q0_orig, new_g_value, T_orig)
+ self.view_trajectory(path, title=plot_title, demo=True)
+
+ for new_T_value in T_vals:
+ plot_title = f"Period = {round(new_T_value, 2)} [sec]"
+
+ _, path = self.recreate_trajectory(q0_orig, g_orig, new_T_value)
+ self.view_trajectory(path, title=plot_title, demo=True)
+
+
+def example_DMP():
+ """
+ Creates a noisy trajectory, fits weights to it, and then adjusts the
+ trajectory by moving its start position, goal position, or period
+ """
+ t = np.arange(0, 3*np.pi/2, 0.01)
+ t1 = np.arange(3*np.pi/2, 2*np.pi, 0.01)[:-1]
+ t2 = np.arange(0, np.pi/2, 0.01)[:-1]
+ t3 = np.arange(np.pi, 3*np.pi/2, 0.01)
+ data_x = t + 0.02*np.random.rand(t.shape[0])
+ data_y = np.concatenate([np.cos(t1) + 0.1*np.random.rand(t1.shape[0]),
+ np.cos(t2) + 0.1*np.random.rand(t2.shape[0]),
+ np.sin(t3) + 0.1*np.random.rand(t3.shape[0])])
+ training_data = np.vstack([data_x, data_y]).T
+
+ period = 3*np.pi/2
+ DMP_controller = DMP(training_data, period)
+
+ DMP_controller.show_DMP_purpose()
+
+
+if __name__ == '__main__':
+ example_DMP()
diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py
index fa1dcc62c4..8664ec1745 100644
--- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py
+++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py
@@ -2,31 +2,36 @@
Mobile robot motion planning sample with Dynamic Window Approach
-author: Atsushi Sakai (@Atsushi_twi)
+author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı
"""
import math
-import numpy as np
-import matplotlib.pyplot as plt
+from enum import Enum
+import matplotlib.pyplot as plt
+import numpy as np
show_animation = True
-def dwa_control(x, u, config, goal, ob):
+def dwa_control(x, config, goal, ob):
"""
- Dynamic Window Approach control
+ Dynamic Window Approach control
"""
-
dw = calc_dynamic_window(x, config)
- u, traj = calc_final_input(x, u, dw, config, goal, ob)
+ u, trajectory = calc_control_and_trajectory(x, dw, config, goal, ob)
+
+ return u, trajectory
- return u, traj
+class RobotType(Enum):
+ circle = 0
+ rectangle = 1
-class Config():
+
+class Config:
"""
simulation parameter class
"""
@@ -35,18 +40,56 @@ def __init__(self):
# robot parameter
self.max_speed = 1.0 # [m/s]
self.min_speed = -0.5 # [m/s]
- self.max_yawrate = 40.0 * math.pi / 180.0 # [rad/s]
+ self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s]
self.max_accel = 0.2 # [m/ss]
- self.max_dyawrate = 40.0 * math.pi / 180.0 # [rad/ss]
- self.v_reso = 0.01 # [m/s]
- self.yawrate_reso = 0.1 * math.pi / 180.0 # [rad/s]
+ self.max_delta_yaw_rate = 40.0 * math.pi / 180.0 # [rad/ss]
+ self.v_resolution = 0.01 # [m/s]
+ self.yaw_rate_resolution = 0.1 * math.pi / 180.0 # [rad/s]
self.dt = 0.1 # [s] Time tick for motion prediction
self.predict_time = 3.0 # [s]
self.to_goal_cost_gain = 0.15
self.speed_cost_gain = 1.0
self.obstacle_cost_gain = 1.0
+ self.robot_stuck_flag_cons = 0.001 # constant to prevent robot stucked
+ self.robot_type = RobotType.circle
+
+ # if robot_type == RobotType.circle
+ # Also used to check if goal is reached in both types
self.robot_radius = 1.0 # [m] for collision check
+ # if robot_type == RobotType.rectangle
+ self.robot_width = 0.5 # [m] for collision check
+ self.robot_length = 1.2 # [m] for collision check
+ # obstacles [x(m) y(m), ....]
+ self.ob = np.array([[-1, -1],
+ [0, 2],
+ [4.0, 2.0],
+ [5.0, 4.0],
+ [5.0, 5.0],
+ [5.0, 6.0],
+ [5.0, 9.0],
+ [8.0, 9.0],
+ [7.0, 9.0],
+ [8.0, 10.0],
+ [9.0, 11.0],
+ [12.0, 13.0],
+ [12.0, 12.0],
+ [15.0, 15.0],
+ [13.0, 13.0]
+ ])
+
+ @property
+ def robot_type(self):
+ return self._robot_type
+
+ @robot_type.setter
+ def robot_type(self, value):
+ if not isinstance(value, RobotType):
+ raise TypeError("robot_type must be an instance of RobotType")
+ self._robot_type = value
+
+
+config = Config()
def motion(x, u, dt):
@@ -70,15 +113,15 @@ def calc_dynamic_window(x, config):
# Dynamic window from robot specification
Vs = [config.min_speed, config.max_speed,
- -config.max_yawrate, config.max_yawrate]
+ -config.max_yaw_rate, config.max_yaw_rate]
# Dynamic window from motion model
Vd = [x[3] - config.max_accel * config.dt,
x[3] + config.max_accel * config.dt,
- x[4] - config.max_dyawrate * config.dt,
- x[4] + config.max_dyawrate * config.dt]
+ x[4] - config.max_delta_yaw_rate * config.dt,
+ x[4] + config.max_delta_yaw_rate * config.dt]
- # [vmin,vmax, yawrate min, yawrate max]
+ # [v_min, v_max, yaw_rate_min, yaw_rate_max]
dw = [max(Vs[0], Vd[0]), min(Vs[1], Vd[1]),
max(Vs[2], Vd[2]), min(Vs[3], Vd[3])]
@@ -91,37 +134,35 @@ def predict_trajectory(x_init, v, y, config):
"""
x = np.array(x_init)
- traj = np.array(x)
+ trajectory = np.array(x)
time = 0
while time <= config.predict_time:
x = motion(x, [v, y], config.dt)
- traj = np.vstack((traj, x))
+ trajectory = np.vstack((trajectory, x))
time += config.dt
- return traj
+ return trajectory
-def calc_final_input(x, u, dw, config, goal, ob):
+def calc_control_and_trajectory(x, dw, config, goal, ob):
"""
- calculation final input with dinamic window
+ calculation final input with dynamic window
"""
x_init = x[:]
min_cost = float("inf")
best_u = [0.0, 0.0]
- best_traj = np.array([x])
-
- # evalucate all trajectory with sampled input in dynamic window
- for v in np.arange(dw[0], dw[1], config.v_reso):
- for y in np.arange(dw[2], dw[3], config.yawrate_reso):
+ best_trajectory = np.array([x])
- traj = predict_trajectory(x_init, v, y, config)
+ # evaluate all trajectory with sampled input in dynamic window
+ for v in np.arange(dw[0], dw[1], config.v_resolution):
+ for y in np.arange(dw[2], dw[3], config.yaw_rate_resolution):
+ trajectory = predict_trajectory(x_init, v, y, config)
# calc cost
- to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(traj, goal, config)
- speed_cost = config.speed_cost_gain * \
- (config.max_speed - traj[-1, 3])
- ob_cost = config.obstacle_cost_gain*calc_obstacle_cost(traj, ob, config)
+ to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(trajectory, goal)
+ speed_cost = config.speed_cost_gain * (config.max_speed - trajectory[-1, 3])
+ ob_cost = config.obstacle_cost_gain * calc_obstacle_cost(trajectory, ob, config)
final_cost = to_goal_cost + speed_cost + ob_cost
@@ -129,45 +170,60 @@ def calc_final_input(x, u, dw, config, goal, ob):
if min_cost >= final_cost:
min_cost = final_cost
best_u = [v, y]
- best_traj = traj
-
- return best_u, best_traj
-
-
-def calc_obstacle_cost(traj, ob, config):
+ best_trajectory = trajectory
+ if abs(best_u[0]) < config.robot_stuck_flag_cons \
+ and abs(x[3]) < config.robot_stuck_flag_cons:
+ # to ensure the robot do not get stuck in
+ # best v=0 m/s (in front of an obstacle) and
+ # best omega=0 rad/s (heading to the goal with
+ # angle difference of 0)
+ best_u[1] = -config.max_delta_yaw_rate
+ return best_u, best_trajectory
+
+
+def calc_obstacle_cost(trajectory, ob, config):
"""
- calc obstacle cost inf: collision
+ calc obstacle cost inf: collision
"""
-
- skip_n = 2 # for speed up
- minr = float("inf")
-
- for ii in range(0, len(traj[:, 1]), skip_n):
- for i in range(len(ob[:, 0])):
- ox = ob[i, 0]
- oy = ob[i, 1]
- dx = traj[ii, 0] - ox
- dy = traj[ii, 1] - oy
-
- r = math.sqrt(dx**2 + dy**2)
- if r <= config.robot_radius:
- return float("Inf") # collision
-
- if minr >= r:
- minr = r
-
- return 1.0 / minr # OK
-
-
-def calc_to_goal_cost(traj, goal, config):
+ ox = ob[:, 0]
+ oy = ob[:, 1]
+ dx = trajectory[:, 0] - ox[:, None]
+ dy = trajectory[:, 1] - oy[:, None]
+ r = np.hypot(dx, dy)
+
+ if config.robot_type == RobotType.rectangle:
+ yaw = trajectory[:, 2]
+ rot = np.array([[np.cos(yaw), -np.sin(yaw)], [np.sin(yaw), np.cos(yaw)]])
+ rot = np.transpose(rot, [2, 0, 1])
+ local_ob = ob[:, None] - trajectory[:, 0:2]
+ local_ob = local_ob.reshape(-1, local_ob.shape[-1])
+ local_ob = np.array([local_ob @ x for x in rot])
+ local_ob = local_ob.reshape(-1, local_ob.shape[-1])
+ upper_check = local_ob[:, 0] <= config.robot_length / 2
+ right_check = local_ob[:, 1] <= config.robot_width / 2
+ bottom_check = local_ob[:, 0] >= -config.robot_length / 2
+ left_check = local_ob[:, 1] >= -config.robot_width / 2
+ if (np.logical_and(np.logical_and(upper_check, right_check),
+ np.logical_and(bottom_check, left_check))).any():
+ return float("Inf")
+ elif config.robot_type == RobotType.circle:
+ if np.array(r <= config.robot_radius).any():
+ return float("Inf")
+
+ min_r = np.min(r)
+ return 1.0 / min_r # OK
+
+
+def calc_to_goal_cost(trajectory, goal):
"""
calc to goal cost with angle difference
"""
- dx = goal[0] - traj[-1, 0]
- dy = goal[1] - traj[-1, 1]
+ dx = goal[0] - trajectory[-1, 0]
+ dy = goal[1] - trajectory[-1, 1]
error_angle = math.atan2(dy, dx)
- cost = abs(error_angle - traj[-1, 2])
+ cost_angle = error_angle - trajectory[-1, 2]
+ cost = abs(math.atan2(math.sin(cost_angle), math.cos(cost_angle)))
return cost
@@ -178,60 +234,75 @@ def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover
plt.plot(x, y)
-def main(gx=10, gy=10):
+def plot_robot(x, y, yaw, config): # pragma: no cover
+ if config.robot_type == RobotType.rectangle:
+ outline = np.array([[-config.robot_length / 2, config.robot_length / 2,
+ (config.robot_length / 2), -config.robot_length / 2,
+ -config.robot_length / 2],
+ [config.robot_width / 2, config.robot_width / 2,
+ - config.robot_width / 2, -config.robot_width / 2,
+ config.robot_width / 2]])
+ Rot1 = np.array([[math.cos(yaw), math.sin(yaw)],
+ [-math.sin(yaw), math.cos(yaw)]])
+ outline = (outline.T.dot(Rot1)).T
+ outline[0, :] += x
+ outline[1, :] += y
+ plt.plot(np.array(outline[0, :]).flatten(),
+ np.array(outline[1, :]).flatten(), "-k")
+ elif config.robot_type == RobotType.circle:
+ circle = plt.Circle((x, y), config.robot_radius, color="b")
+ plt.gcf().gca().add_artist(circle)
+ out_x, out_y = (np.array([x, y]) +
+ np.array([np.cos(yaw), np.sin(yaw)]) * config.robot_radius)
+ plt.plot([x, out_x], [y, out_y], "-k")
+
+
+def main(gx=10.0, gy=10.0, robot_type=RobotType.circle):
print(__file__ + " start!!")
# initial state [x(m), y(m), yaw(rad), v(m/s), omega(rad/s)]
x = np.array([0.0, 0.0, math.pi / 8.0, 0.0, 0.0])
# goal position [x(m), y(m)]
goal = np.array([gx, gy])
- # obstacles [x(m) y(m), ....]
- ob = np.array([[-1, -1],
- [0, 2],
- [4.0, 2.0],
- [5.0, 4.0],
- [5.0, 5.0],
- [5.0, 6.0],
- [5.0, 9.0],
- [8.0, 9.0],
- [7.0, 9.0],
- [12.0, 12.0]
- ])
-
- # input [forward speed, yawrate]
- u = np.array([0.0, 0.0])
- config = Config()
- traj = np.array(x)
- while True:
- u, ptraj = dwa_control(x, u, config, goal, ob)
+ # input [forward speed, yaw_rate]
- x = motion(x, u, config.dt) # simulate robot
- traj = np.vstack((traj, x)) # store state history
+ config.robot_type = robot_type
+ trajectory = np.array(x)
+ ob = config.ob
+ while True:
+ u, predicted_trajectory = dwa_control(x, config, goal, ob)
+ x = motion(x, u, config.dt) # simulate robot
+ trajectory = np.vstack((trajectory, x)) # store state history
if show_animation:
plt.cla()
- plt.plot(ptraj[:, 0], ptraj[:, 1], "-g")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g")
plt.plot(x[0], x[1], "xr")
plt.plot(goal[0], goal[1], "xb")
plt.plot(ob[:, 0], ob[:, 1], "ok")
+ plot_robot(x[0], x[1], x[2], config)
plot_arrow(x[0], x[1], x[2])
plt.axis("equal")
plt.grid(True)
plt.pause(0.0001)
# check reaching goal
- dist_to_goal = math.sqrt((x[0] - goal[0])**2 + (x[1] - goal[1])**2)
+ dist_to_goal = math.hypot(x[0] - goal[0], x[1] - goal[1])
if dist_to_goal <= config.robot_radius:
print("Goal!!")
break
print("Done")
if show_animation:
- plt.plot(traj[:, 0], traj[:, 1], "-r")
+ plt.plot(trajectory[:, 0], trajectory[:, 1], "-r")
plt.pause(0.0001)
-
- plt.show()
+ plt.show()
if __name__ == '__main__':
- main()
+ main(robot_type=RobotType.rectangle)
+ # main(robot_type=RobotType.circle)
diff --git a/PathPlanning/ElasticBands/elastic_bands.py b/PathPlanning/ElasticBands/elastic_bands.py
new file mode 100644
index 0000000000..77d4e6e399
--- /dev/null
+++ b/PathPlanning/ElasticBands/elastic_bands.py
@@ -0,0 +1,300 @@
+"""
+Elastic Bands
+
+author: Wang Zheng (@Aglargil)
+
+Reference:
+
+- [Elastic Bands: Connecting Path Planning and Control]
+(http://www8.cs.umu.se/research/ifor/dl/Control/elastic%20bands.pdf)
+"""
+
+import numpy as np
+import sys
+import pathlib
+import matplotlib.pyplot as plt
+from matplotlib.patches import Circle
+
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
+from Mapping.DistanceMap.distance_map import compute_sdf_scipy
+
+# Elastic Bands Params
+MAX_BUBBLE_RADIUS = 100
+MIN_BUBBLE_RADIUS = 10
+RHO0 = 20.0 # Maximum distance for applying repulsive force
+KC = 0.05 # Contraction force gain
+KR = -0.1 # Repulsive force gain
+LAMBDA = 0.7 # Overlap constraint factor
+STEP_SIZE = 3.0 # Step size for calculating gradient
+
+# Visualization Params
+ENABLE_PLOT = True
+# ENABLE_INTERACTIVE is True allows user to add obstacles by left clicking
+# and add path points by right clicking and start planning by middle clicking
+ENABLE_INTERACTIVE = False
+# ENABLE_SAVE_DATA is True allows saving the path and obstacles which added
+# by user in interactive mode to file
+ENABLE_SAVE_DATA = False
+MAX_ITER = 50
+
+
+class Bubble:
+ def __init__(self, position, radius):
+ self.pos = np.array(position) # Bubble center coordinates [x, y]
+ self.radius = radius # Safety distance radius ρ(b)
+ if self.radius > MAX_BUBBLE_RADIUS:
+ self.radius = MAX_BUBBLE_RADIUS
+ if self.radius < MIN_BUBBLE_RADIUS:
+ self.radius = MIN_BUBBLE_RADIUS
+
+
+class ElasticBands:
+ def __init__(
+ self,
+ initial_path,
+ obstacles,
+ rho0=RHO0,
+ kc=KC,
+ kr=KR,
+ lambda_=LAMBDA,
+ step_size=STEP_SIZE,
+ ):
+ self.distance_map = compute_sdf_scipy(obstacles)
+ self.bubbles = [
+ Bubble(p, self.compute_rho(p)) for p in initial_path
+ ] # Initialize bubble chain
+ self.kc = kc # Contraction force gain
+ self.kr = kr # Repulsive force gain
+ self.rho0 = rho0 # Maximum distance for applying repulsive force
+ self.lambda_ = lambda_ # Overlap constraint factor
+ self.step_size = step_size # Step size for calculating gradient
+ self._maintain_overlap()
+
+ def compute_rho(self, position):
+ """Compute the distance field value at the position"""
+ return self.distance_map[int(position[0]), int(position[1])]
+
+ def contraction_force(self, i):
+ """Calculate internal contraction force for the i-th bubble"""
+ if i == 0 or i == len(self.bubbles) - 1:
+ return np.zeros(2)
+
+ prev = self.bubbles[i - 1].pos
+ next_ = self.bubbles[i + 1].pos
+ current = self.bubbles[i].pos
+
+ # f_c = kc * ( (prev-current)/|prev-current| + (next-current)/|next-current| )
+ dir_prev = (prev - current) / (np.linalg.norm(prev - current) + 1e-6)
+ dir_next = (next_ - current) / (np.linalg.norm(next_ - current) + 1e-6)
+ return self.kc * (dir_prev + dir_next)
+
+ def repulsive_force(self, i):
+ """Calculate external repulsive force for the i-th bubble"""
+ h = self.step_size # Step size
+ b = self.bubbles[i].pos
+ rho = self.bubbles[i].radius
+
+ if rho >= self.rho0:
+ return np.zeros(2)
+
+ # Finite difference approximation of the gradient ∂ρ/∂b
+ dx = np.array([h, 0])
+ dy = np.array([0, h])
+ grad_x = (self.compute_rho(b - dx) - self.compute_rho(b + dx)) / (2 * h)
+ grad_y = (self.compute_rho(b - dy) - self.compute_rho(b + dy)) / (2 * h)
+ grad = np.array([grad_x, grad_y])
+
+ return self.kr * (self.rho0 - rho) * grad
+
+ def update_bubbles(self):
+ """Update bubble positions"""
+ new_bubbles = []
+ for i in range(len(self.bubbles)):
+ if i == 0 or i == len(self.bubbles) - 1:
+ new_bubbles.append(self.bubbles[i]) # Fixed start and end points
+ continue
+
+ f_total = self.contraction_force(i) + self.repulsive_force(i)
+ v = self.bubbles[i - 1].pos - self.bubbles[i + 1].pos
+
+ # Remove tangential component
+ f_star = f_total - f_total * v * v / (np.linalg.norm(v) ** 2 + 1e-6)
+
+ alpha = self.bubbles[i].radius # Adaptive step size
+ new_pos = self.bubbles[i].pos + alpha * f_star
+ new_pos = np.clip(new_pos, 0, 499)
+ new_radius = self.compute_rho(new_pos)
+
+ # Update bubble and maintain overlap constraint
+ new_bubble = Bubble(new_pos, new_radius)
+ new_bubbles.append(new_bubble)
+
+ self.bubbles = new_bubbles
+ self._maintain_overlap()
+
+ def _maintain_overlap(self):
+ """Maintain bubble chain continuity (simplified insertion/deletion mechanism)"""
+ # Insert bubbles
+ i = 0
+ while i < len(self.bubbles) - 1:
+ bi, bj = self.bubbles[i], self.bubbles[i + 1]
+ dist = np.linalg.norm(bi.pos - bj.pos)
+ if dist > self.lambda_ * (bi.radius + bj.radius):
+ new_pos = (bi.pos + bj.pos) / 2
+ rho = self.compute_rho(
+ new_pos
+ ) # Calculate new radius using environment model
+ self.bubbles.insert(i + 1, Bubble(new_pos, rho))
+ i += 2 # Skip the processed region
+ else:
+ i += 1
+
+ # Delete redundant bubbles
+ i = 1
+ while i < len(self.bubbles) - 1:
+ prev = self.bubbles[i - 1]
+ next_ = self.bubbles[i + 1]
+ dist = np.linalg.norm(prev.pos - next_.pos)
+ if dist <= self.lambda_ * (prev.radius + next_.radius):
+ del self.bubbles[i] # Delete if redundant
+ else:
+ i += 1
+
+
+class ElasticBandsVisualizer:
+ def __init__(self):
+ self.obstacles = np.zeros((500, 500))
+ self.obstacles_points = []
+ self.path_points = []
+ self.elastic_band = None
+ self.running = True
+
+ if ENABLE_PLOT:
+ self.fig, self.ax = plt.subplots(figsize=(8, 8))
+ self.fig.canvas.mpl_connect("close_event", self.on_close)
+ self.ax.set_xlim(0, 500)
+ self.ax.set_ylim(0, 500)
+
+ if ENABLE_INTERACTIVE:
+ self.path_points = [] # Add a list to store path points
+ # Connect mouse events
+ self.fig.canvas.mpl_connect("button_press_event", self.on_click)
+ else:
+ self.path_points = np.load(pathlib.Path(__file__).parent / "path.npy")
+ self.obstacles_points = np.load(
+ pathlib.Path(__file__).parent / "obstacles.npy"
+ )
+ for x, y in self.obstacles_points:
+ self.add_obstacle(x, y)
+ self.plan_path()
+
+ self.plot_background()
+
+ def on_close(self, event):
+ """Handle window close event"""
+ self.running = False
+ plt.close("all") # Close all figure windows
+
+ def plot_background(self):
+ """Plot the background grid"""
+ if not ENABLE_PLOT or not self.running:
+ return
+
+ self.ax.cla()
+ self.ax.set_xlim(0, 500)
+ self.ax.set_ylim(0, 500)
+ self.ax.grid(True)
+
+ if ENABLE_INTERACTIVE:
+ self.ax.set_title(
+ "Elastic Bands Path Planning\n"
+ "Left click: Add obstacles\n"
+ "Right click: Add path points\n"
+ "Middle click: Start planning",
+ pad=20,
+ )
+ else:
+ self.ax.set_title("Elastic Bands Path Planning", pad=20)
+
+ if self.path_points:
+ self.ax.plot(
+ [p[0] for p in self.path_points],
+ [p[1] for p in self.path_points],
+ "yo",
+ markersize=8,
+ )
+
+ self.ax.imshow(self.obstacles.T, origin="lower", cmap="binary", alpha=0.8)
+ self.ax.plot([], [], color="black", label="obstacles")
+ if self.elastic_band is not None:
+ path = [b.pos.tolist() for b in self.elastic_band.bubbles]
+ path = np.array(path)
+ self.ax.plot(path[:, 0], path[:, 1], "b-", linewidth=2, label="path")
+
+ for bubble in self.elastic_band.bubbles:
+ circle = Circle(
+ bubble.pos, bubble.radius, fill=False, color="g", alpha=0.3
+ )
+ self.ax.add_patch(circle)
+ self.ax.plot(bubble.pos[0], bubble.pos[1], "bo", markersize=10)
+ self.ax.plot([], [], color="green", label="bubbles")
+
+ self.ax.legend(loc="upper right")
+ plt.draw()
+ plt.pause(0.01)
+
+ def add_obstacle(self, x, y):
+ """Add an obstacle at the given coordinates"""
+ size = 30 # Side length of the square
+ half_size = size // 2
+ x_start = max(0, x - half_size)
+ x_end = min(self.obstacles.shape[0], x + half_size)
+ y_start = max(0, y - half_size)
+ y_end = min(self.obstacles.shape[1], y + half_size)
+ self.obstacles[x_start:x_end, y_start:y_end] = 1
+
+ def on_click(self, event):
+ """Handle mouse click events"""
+ if event.inaxes != self.ax:
+ return
+
+ x, y = int(event.xdata), int(event.ydata)
+
+ if event.button == 1: # Left click to add obstacles
+ self.add_obstacle(x, y)
+ self.obstacles_points.append([x, y])
+
+ elif event.button == 3: # Right click to add path points
+ self.path_points.append([x, y])
+
+ elif event.button == 2: # Middle click to end path input and start planning
+ if len(self.path_points) >= 2:
+ if ENABLE_SAVE_DATA:
+ np.save(
+ pathlib.Path(__file__).parent / "path.npy", self.path_points
+ )
+ np.save(
+ pathlib.Path(__file__).parent / "obstacles.npy",
+ self.obstacles_points,
+ )
+ self.plan_path()
+
+ self.plot_background()
+
+ def plan_path(self):
+ """Plan the path"""
+
+ initial_path = self.path_points
+ # Create an elastic band object and optimize
+ self.elastic_band = ElasticBands(initial_path, self.obstacles)
+ for _ in range(MAX_ITER):
+ self.elastic_band.update_bubbles()
+ self.path_points = [b.pos for b in self.elastic_band.bubbles]
+ self.plot_background()
+
+
+if __name__ == "__main__":
+ _ = ElasticBandsVisualizer()
+ if ENABLE_PLOT:
+ plt.show(block=True)
diff --git a/PathPlanning/ElasticBands/obstacles.npy b/PathPlanning/ElasticBands/obstacles.npy
new file mode 100644
index 0000000000..af4376afcf
Binary files /dev/null and b/PathPlanning/ElasticBands/obstacles.npy differ
diff --git a/PathPlanning/ElasticBands/path.npy b/PathPlanning/ElasticBands/path.npy
new file mode 100644
index 0000000000..be7c253d65
Binary files /dev/null and b/PathPlanning/ElasticBands/path.npy differ
diff --git a/PathPlanning/Eta3SplinePath/eta3_spline_path.py b/PathPlanning/Eta3SplinePath/eta3_spline_path.py
index 072b0bb46c..3f685e512f 100644
--- a/PathPlanning/Eta3SplinePath/eta3_spline_path.py
+++ b/PathPlanning/Eta3SplinePath/eta3_spline_path.py
@@ -1,13 +1,13 @@
"""
-\eta^3 polynomials planner
+eta^3 polynomials planner
author: Joe Dinius, Ph.D (https://jwdinius.github.io)
Atsushi Sakai (@Atsushi_twi)
-Ref:
-
-- [\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots](https://ieeexplore.ieee.org/document/4339545/)
+Reference:
+- [eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots]
+(https://ieeexplore.ieee.org/document/4339545/)
"""
@@ -15,23 +15,25 @@
import matplotlib.pyplot as plt
from scipy.integrate import quad
-# NOTE: *_pose is a 3-array: 0 - x coord, 1 - y coord, 2 - orientation angle \theta
+# NOTE: *_pose is a 3-array:
+# 0 - x coord, 1 - y coord, 2 - orientation angle \theta
show_animation = True
-class eta3_path(object):
+class Eta3Path(object):
"""
- eta3_path
+ Eta3Path
input
- segments: list of `eta3_path_segment` instances definining a continuous path
+ segments: a list of `Eta3PathSegment` instances
+ defining a continuous path
"""
def __init__(self, segments):
# ensure input has the correct form
assert(isinstance(segments, list) and isinstance(
- segments[0], eta3_path_segment))
+ segments[0], Eta3PathSegment))
# ensure that each segment begins from the previous segment's end (continuity)
for r, s in zip(segments[:-1], segments[1:]):
assert(np.array_equal(r.end_pose, s.start_pose))
@@ -39,7 +41,7 @@ def __init__(self, segments):
def calc_path_point(self, u):
"""
- eta3_path::calc_path_point
+ Eta3Path::calc_path_point
input
normalized interpolation point along path object, 0 <= u <= len(self.segments)
@@ -47,7 +49,7 @@ def calc_path_point(self, u):
2d (x,y) position vector
"""
- assert(u >= 0 and u <= len(self.segments))
+ assert(0 <= u <= len(self.segments))
if np.isclose(u, len(self.segments)):
segment_idx = len(self.segments) - 1
u = 1.
@@ -57,11 +59,12 @@ def calc_path_point(self, u):
return self.segments[segment_idx].calc_point(u)
-class eta3_path_segment(object):
+class Eta3PathSegment(object):
"""
- eta3_path_segment - constructs an eta^3 path segment based on desired shaping, eta, and curvature vector, kappa.
- If either, or both, of eta and kappa are not set during initialization, they will
- default to zeros.
+ Eta3PathSegment - constructs an eta^3 path segment based on desired
+ shaping, eta, and curvature vector, kappa. If either, or both,
+ of eta and kappa are not set during initialization,
+ they will default to zeros.
input
start_pose - starting pose array (x, y, \theta)
@@ -110,70 +113,96 @@ def __init__(self, start_pose, end_pose, eta=None, kappa=None):
self.coeffs[1, 3] = 1. / 6 * eta[4] * sa + 1. / 6 * \
(eta[0]**3 * kappa[1] + 3. * eta[0] * eta[2] * kappa[0]) * ca
# quartic (u^4)
- self.coeffs[0, 4] = 35. * (end_pose[0] - start_pose[0]) - (20. * eta[0] + 5 * eta[2] + 2. / 3 * eta[4]) * ca \
- + (5. * eta[0]**2 * kappa[0] + 2. / 3 * eta[0]**3 * kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * sa \
- - (15. * eta[1] - 5. / 2 * eta[3] + 1. / 6 * eta[5]) * cb \
- - (5. / 2 * eta[1]**2 * kappa[2] - 1. / 6 * eta[1] **
- 3 * kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * sb
- self.coeffs[1, 4] = 35. * (end_pose[1] - start_pose[1]) - (20. * eta[0] + 5. * eta[2] + 2. / 3 * eta[4]) * sa \
- - (5. * eta[0]**2 * kappa[0] + 2. / 3 * eta[0]**3 * kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * ca \
- - (15. * eta[1] - 5. / 2 * eta[3] + 1. / 6 * eta[5]) * sb \
- + (5. / 2 * eta[1]**2 * kappa[2] - 1. / 6 * eta[1] **
- 3 * kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ tmp1 = 35. * (end_pose[0] - start_pose[0])
+ tmp2 = (20. * eta[0] + 5 * eta[2] + 2. / 3 * eta[4]) * ca
+ tmp3 = (5. * eta[0] ** 2 * kappa[0] + 2. / 3 * eta[0] ** 3 * kappa[1]
+ + 2. * eta[0] * eta[2] * kappa[0]) * sa
+ tmp4 = (15. * eta[1] - 5. / 2 * eta[3] + 1. / 6 * eta[5]) * cb
+ tmp5 = (5. / 2 * eta[1] ** 2 * kappa[2] - 1. / 6 * eta[1] ** 3 *
+ kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * sb
+ self.coeffs[0, 4] = tmp1 - tmp2 + tmp3 - tmp4 - tmp5
+ tmp1 = 35. * (end_pose[1] - start_pose[1])
+ tmp2 = (20. * eta[0] + 5. * eta[2] + 2. / 3 * eta[4]) * sa
+ tmp3 = (5. * eta[0] ** 2 * kappa[0] + 2. / 3 * eta[0] ** 3 * kappa[1]
+ + 2. * eta[0] * eta[2] * kappa[0]) * ca
+ tmp4 = (15. * eta[1] - 5. / 2 * eta[3] + 1. / 6 * eta[5]) * sb
+ tmp5 = (5. / 2 * eta[1] ** 2 * kappa[2] - 1. / 6 * eta[1] ** 3 *
+ kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ self.coeffs[1, 4] = tmp1 - tmp2 - tmp3 - tmp4 + tmp5
# quintic (u^5)
- self.coeffs[0, 5] = -84. * (end_pose[0] - start_pose[0]) + (45. * eta[0] + 10. * eta[2] + eta[4]) * ca \
- - (10. * eta[0]**2 * kappa[0] + eta[0]**3 * kappa[1] + 3. * eta[0] * eta[2] * kappa[0]) * sa \
- + (39. * eta[1] - 7. * eta[3] + 1. / 2 * eta[5]) * cb \
- + (7. * eta[1]**2 * kappa[2] - 1. / 2 * eta[1]**3 *
- kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * sb
- self.coeffs[1, 5] = -84. * (end_pose[1] - start_pose[1]) + (45. * eta[0] + 10. * eta[2] + eta[4]) * sa \
- + (10. * eta[0]**2 * kappa[0] + eta[0]**3 * kappa[1] + 3. * eta[0] * eta[2] * kappa[0]) * ca \
- + (39. * eta[1] - 7. * eta[3] + 1. / 2 * eta[5]) * sb \
- - (7. * eta[1]**2 * kappa[2] - 1. / 2 * eta[1]**3 *
- kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ tmp1 = -84. * (end_pose[0] - start_pose[0])
+ tmp2 = (45. * eta[0] + 10. * eta[2] + eta[4]) * ca
+ tmp3 = (10. * eta[0] ** 2 * kappa[0] + eta[0] ** 3 * kappa[1] + 3. *
+ eta[0] * eta[2] * kappa[0]) * sa
+ tmp4 = (39. * eta[1] - 7. * eta[3] + 1. / 2 * eta[5]) * cb
+ tmp5 = + (7. * eta[1] ** 2 * kappa[2] - 1. / 2 * eta[1] ** 3 * kappa[3]
+ - 3. / 2 * eta[1] * eta[3] * kappa[2]) * sb
+ self.coeffs[0, 5] = tmp1 + tmp2 - tmp3 + tmp4 + tmp5
+ tmp1 = -84. * (end_pose[1] - start_pose[1])
+ tmp2 = (45. * eta[0] + 10. * eta[2] + eta[4]) * sa
+ tmp3 = (10. * eta[0] ** 2 * kappa[0] + eta[0] ** 3 * kappa[1] + 3. *
+ eta[0] * eta[2] * kappa[0]) * ca
+ tmp4 = (39. * eta[1] - 7. * eta[3] + 1. / 2 * eta[5]) * sb
+ tmp5 = - (7. * eta[1] ** 2 * kappa[2] - 1. / 2 * eta[1] ** 3 * kappa[3]
+ - 3. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ self.coeffs[1, 5] = tmp1 + tmp2 + tmp3 + tmp4 + tmp5
# sextic (u^6)
- self.coeffs[0, 6] = 70. * (end_pose[0] - start_pose[0]) - (36. * eta[0] + 15. / 2 * eta[2] + 2. / 3 * eta[4]) * ca \
- + (15. / 2 * eta[0]**2 * kappa[0] + 2. / 3 * eta[0]**3 * kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * sa \
- - (34. * eta[1] - 13. / 2 * eta[3] + 1. / 2 * eta[5]) * cb \
- - (13. / 2 * eta[1]**2 * kappa[2] - 1. / 2 * eta[1] **
- 3 * kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * sb
- self.coeffs[1, 6] = 70. * (end_pose[1] - start_pose[1]) - (36. * eta[0] + 15. / 2 * eta[2] + 2. / 3 * eta[4]) * sa \
- - (15. / 2 * eta[0]**2 * kappa[0] + 2. / 3 * eta[0]**3 * kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * ca \
- - (34. * eta[1] - 13. / 2 * eta[3] + 1. / 2 * eta[5]) * sb \
- + (13. / 2 * eta[1]**2 * kappa[2] - 1. / 2 * eta[1] **
- 3 * kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ tmp1 = 70. * (end_pose[0] - start_pose[0])
+ tmp2 = (36. * eta[0] + 15. / 2 * eta[2] + 2. / 3 * eta[4]) * ca
+ tmp3 = + (15. / 2 * eta[0] ** 2 * kappa[0] + 2. / 3 * eta[0] ** 3 *
+ kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * sa
+ tmp4 = (34. * eta[1] - 13. / 2 * eta[3] + 1. / 2 * eta[5]) * cb
+ tmp5 = - (13. / 2 * eta[1] ** 2 * kappa[2] - 1. / 2 * eta[1] ** 3 *
+ kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * sb
+ self.coeffs[0, 6] = tmp1 - tmp2 + tmp3 - tmp4 + tmp5
+ tmp1 = 70. * (end_pose[1] - start_pose[1])
+ tmp2 = - (36. * eta[0] + 15. / 2 * eta[2] + 2. / 3 * eta[4]) * sa
+ tmp3 = - (15. / 2 * eta[0] ** 2 * kappa[0] + 2. / 3 * eta[0] ** 3 *
+ kappa[1] + 2. * eta[0] * eta[2] * kappa[0]) * ca
+ tmp4 = - (34. * eta[1] - 13. / 2 * eta[3] + 1. / 2 * eta[5]) * sb
+ tmp5 = + (13. / 2 * eta[1] ** 2 * kappa[2] - 1. / 2 * eta[1] ** 3 *
+ kappa[3] - 3. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ self.coeffs[1, 6] = tmp1 + tmp2 + tmp3 + tmp4 + tmp5
# septic (u^7)
- self.coeffs[0, 7] = -20. * (end_pose[0] - start_pose[0]) + (10. * eta[0] + 2. * eta[2] + 1. / 6 * eta[4]) * ca \
- - (2. * eta[0]**2 * kappa[0] + 1. / 6 * eta[0]**3 * kappa[1] + 1. / 2 * eta[0] * eta[2] * kappa[0]) * sa \
- + (10. * eta[1] - 2. * eta[3] + 1. / 6 * eta[5]) * cb \
- + (2. * eta[1]**2 * kappa[2] - 1. / 6 * eta[1]**3 *
- kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * sb
- self.coeffs[1, 7] = -20. * (end_pose[1] - start_pose[1]) + (10. * eta[0] + 2. * eta[2] + 1. / 6 * eta[4]) * sa \
- + (2. * eta[0]**2 * kappa[0] + 1. / 6 * eta[0]**3 * kappa[1] + 1. / 2 * eta[0] * eta[2] * kappa[0]) * ca \
- + (10. * eta[1] - 2. * eta[3] + 1. / 6 * eta[5]) * sb \
- - (2. * eta[1]**2 * kappa[2] - 1. / 6 * eta[1]**3 *
- kappa[3] - 1. / 2 * eta[1] * eta[3] * kappa[2]) * cb
-
- self.s_dot = lambda u: max(np.linalg.norm(self.coeffs[:, 1:].dot(np.array(
- [1, 2. * u, 3. * u**2, 4. * u**3, 5. * u**4, 6. * u**5, 7. * u**6]))), 1e-6)
+ tmp1 = -20. * (end_pose[0] - start_pose[0])
+ tmp2 = (10. * eta[0] + 2. * eta[2] + 1. / 6 * eta[4]) * ca
+ tmp3 = - (2. * eta[0] ** 2 * kappa[0] + 1. / 6 * eta[0] ** 3 * kappa[1]
+ + 1. / 2 * eta[0] * eta[2] * kappa[0]) * sa
+ tmp4 = (10. * eta[1] - 2. * eta[3] + 1. / 6 * eta[5]) * cb
+ tmp5 = (2. * eta[1] ** 2 * kappa[2] - 1. / 6 * eta[1] ** 3 * kappa[3]
+ - 1. / 2 * eta[1] * eta[3] * kappa[2]) * sb
+ self.coeffs[0, 7] = tmp1 + tmp2 + tmp3 + tmp4 + tmp5
+
+ tmp1 = -20. * (end_pose[1] - start_pose[1])
+ tmp2 = (10. * eta[0] + 2. * eta[2] + 1. / 6 * eta[4]) * sa
+ tmp3 = (2. * eta[0] ** 2 * kappa[0] + 1. / 6 * eta[0] ** 3 * kappa[1]
+ + 1. / 2 * eta[0] * eta[2] * kappa[0]) * ca
+ tmp4 = (10. * eta[1] - 2. * eta[3] + 1. / 6 * eta[5]) * sb
+ tmp5 = - (2. * eta[1] ** 2 * kappa[2] - 1. / 6 * eta[1] ** 3 * kappa[3]
+ - 1. / 2 * eta[1] * eta[3] * kappa[2]) * cb
+ self.coeffs[1, 7] = tmp1 + tmp2 + tmp3 + tmp4 + tmp5
+ self.s_dot = lambda u: max(np.linalg.norm(
+ self.coeffs[:, 1:].dot(np.array(
+ [1, 2. * u, 3. * u**2, 4. * u**3,
+ 5. * u**4, 6. * u**5, 7. * u**6]))), 1e-6)
self.f_length = lambda ue: quad(lambda u: self.s_dot(u), 0, ue)
self.segment_length = self.f_length(1)[0]
def calc_point(self, u):
"""
- eta3_path_segment::calc_point
+ Eta3PathSegment::calc_point
input
u - parametric representation of a point along the segment, 0 <= u <= 1
returns
(x,y) of point along the segment
"""
- assert(u >= 0 and u <= 1)
+ assert(0 <= u <= 1)
return self.coeffs.dot(np.array([1, u, u**2, u**3, u**4, u**5, u**6, u**7]))
def calc_deriv(self, u, order=1):
"""
- eta3_path_segment::calc_deriv
+ Eta3PathSegment::calc_deriv
input
u - parametric representation of a point along the segment, 0 <= u <= 1
@@ -181,8 +210,8 @@ def calc_deriv(self, u, order=1):
(d^nx/du^n,d^ny/du^n) of point along the segment, for 0 < n <= 2
"""
- assert(u >= 0 and u <= 1)
- assert(order > 0 and order <= 2)
+ assert(0 <= u <= 1)
+ assert(0 < order <= 2)
if order == 1:
return self.coeffs[:, 1:].dot(np.array([1, 2. * u, 3. * u**2, 4. * u**3, 5. * u**4, 6. * u**5, 7. * u**6]))
@@ -199,10 +228,10 @@ def test1():
# NOTE: The ordering on kappa is [kappa_A, kappad_A, kappa_B, kappad_B], with kappad_* being the curvature derivative
kappa = [0, 0, 0, 0]
eta = [i, i, 0, 0, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
- path = eta3_path(path_segments)
+ path = Eta3Path(path_segments)
# interpolate at several points along the path
ui = np.linspace(0, len(path_segments), 1001)
@@ -213,6 +242,10 @@ def test1():
if show_animation:
# plot the path
plt.plot(pos[0, :], pos[1, :])
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.pause(1.0)
if show_animation:
@@ -229,10 +262,10 @@ def test2():
# NOTE: The ordering on kappa is [kappa_A, kappad_A, kappa_B, kappad_B], with kappad_* being the curvature derivative
kappa = [0, 0, 0, 0]
eta = [0, 0, (i - 5) * 20, (5 - i) * 20, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
- path = eta3_path(path_segments)
+ path = Eta3Path(path_segments)
# interpolate at several points along the path
ui = np.linspace(0, len(path_segments), 1001)
@@ -258,7 +291,7 @@ def test3():
# NOTE: The ordering on kappa is [kappa_A, kappad_A, kappa_B, kappad_B], with kappad_* being the curvature derivative
kappa = [0, 0, 0, 0]
eta = [4.27, 4.27, 0, 0, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 2: line segment
@@ -266,7 +299,7 @@ def test3():
end_pose = [5.5, 1.5, 0]
kappa = [0, 0, 0, 0]
eta = [0, 0, 0, 0, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 3: cubic spiral
@@ -274,7 +307,7 @@ def test3():
end_pose = [7.4377, 1.8235, 0.6667]
kappa = [0, 0, 1, 1]
eta = [1.88, 1.88, 0, 0, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 4: generic twirl arc
@@ -282,7 +315,7 @@ def test3():
end_pose = [7.8, 4.3, 1.8]
kappa = [1, 1, 0.5, 0]
eta = [7, 10, 10, -10, 4, 4]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 5: circular arc
@@ -290,11 +323,11 @@ def test3():
end_pose = [5.4581, 5.8064, 3.3416]
kappa = [0.5, 0, 0.5, 0]
eta = [2.98, 2.98, 0, 0, 0, 0]
- path_segments.append(eta3_path_segment(
+ path_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# construct the whole path
- path = eta3_path(path_segments)
+ path = Eta3Path(path_segments)
# interpolate at several points along the path
ui = np.linspace(0, len(path_segments), 1001)
diff --git a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py
index 22928354a5..e72d33261e 100644
--- a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py
+++ b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py
@@ -1,13 +1,14 @@
"""
-\eta^3 polynomials trajectory planner
+eta^3 polynomials trajectory planner
author: Joe Dinius, Ph.D (https://jwdinius.github.io)
Atsushi Sakai (@Atsushi_twi)
Refs:
-- https://jwdinius.github.io/blog/2018/eta3traj
-- [\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots](https://ieeexplore.ieee.org/document/4339545/)
+- https://jwdinius.github.io/blog/2018/eta3traj/
+- [eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots]
+(https://ieeexplore.ieee.org/document/4339545/)
"""
@@ -15,24 +16,20 @@
import matplotlib.pyplot as plt
from matplotlib.collections import LineCollection
import sys
-import os
-sys.path.append(os.path.relpath("../Eta3SplinePath"))
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
-try:
- from eta3_spline_path import eta3_path, eta3_path_segment
-except:
- raise
+from Eta3SplinePath.eta3_spline_path import Eta3Path, Eta3PathSegment
show_animation = True
class MaxVelocityNotReached(Exception):
def __init__(self, actual_vel, max_vel):
- self.message = 'Actual velocity {} does not equal desired max velocity {}!'.format(
- actual_vel, max_vel)
+ self.message = f'Actual velocity {actual_vel} does not equal desired max velocity {max_vel}!'
-class eta3_trajectory(eta3_path):
+class Eta3SplineTrajectory(Eta3Path):
"""
eta3_trajectory
@@ -41,10 +38,10 @@ class eta3_trajectory(eta3_path):
"""
def __init__(self, segments, max_vel, v0=0.0, a0=0.0, max_accel=2.0, max_jerk=5.0):
- # ensure that all inputs obey the assumptions of the model
+ # ensure that all inputs obey the assumptions of the model
assert max_vel > 0 and v0 >= 0 and a0 >= 0 and max_accel > 0 and max_jerk > 0 \
and a0 <= max_accel and v0 <= max_vel
- super(eta3_trajectory, self).__init__(segments=segments)
+ super(__class__, self).__init__(segments=segments)
self.total_length = sum([s.segment_length for s in self.segments])
self.max_vel = float(max_vel)
self.v0 = float(v0)
@@ -61,19 +58,19 @@ def __init__(self, segments, max_vel, v0=0.0, a0=0.0, max_accel=2.0, max_jerk=5.
self.prev_seg_id = 0
def velocity_profile(self):
- ''' /~~~~~----------------~~~~~\
- / \
- / \
- / \
- / \
- (v=v0, a=a0) ~~~~~ \
- \
- \~~~~~ (vf=0, af=0)
+ r""" /~~~~~----------------\
+ / \
+ / \
+ / \
+ / \
+ (v=v0, a=a0) ~~~~~ \
+ \
+ \ ~~~~~ (vf=0, af=0)
pos.|pos.|neg.| cruise at |neg.| neg. |neg.
max |max.|max.| max. |max.| max. |max.
jerk|acc.|jerk| velocity |jerk| acc. |jerk
index 0 1 2 3 (optional) 4 5 6
- '''
+ """
# delta_a: accel change from initial position to end of maximal jerk section
delta_a = self.max_accel - self.a0
# t_s1: time of traversal of maximal jerk section
@@ -112,7 +109,6 @@ def velocity_profile(self):
self.seg_lengths = np.zeros((7,))
# Section 0: max jerk up to max acceleration
- index = 0
self.times[0] = t_s1
self.vels[0] = v_s1
self.seg_lengths[0] = s_s1
@@ -169,7 +165,7 @@ def velocity_profile(self):
try:
assert np.isclose(self.vels[index], 0)
except AssertionError as e:
- print('The final velocity {} is not zero'.format(self.vels[index]))
+ print(f'The final velocity {self.vels[index]} is not zero')
raise e
self.seg_lengths[index] = s_sf
@@ -195,7 +191,7 @@ def f(u):
def fprime(u):
return self.segments[seg_id].s_dot(u)
- while (ui >= 0 and ui <= 1) and abs(f(ui)) > tol:
+ while (0 <= ui <= 1) and abs(f(ui)) > tol:
ui -= f(ui) / fprime(ui)
ui = max(0, min(ui, 1))
return ui
@@ -301,11 +297,11 @@ def test1(max_vel=0.5):
# NOTE: The ordering on kappa is [kappa_A, kappad_A, kappa_B, kappad_B], with kappad_* being the curvature derivative
kappa = [0, 0, 0, 0]
eta = [i, i, 0, 0, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
- traj = eta3_trajectory(trajectory_segments,
- max_vel=max_vel, max_accel=0.5)
+ traj = Eta3SplineTrajectory(trajectory_segments,
+ max_vel=max_vel, max_accel=0.5)
# interpolate at several points along the path
times = np.linspace(0, traj.total_time, 101)
@@ -335,11 +331,11 @@ def test2(max_vel=0.5):
# NOTE: INTEGRATOR ERROR EXPLODES WHEN eta[:1] IS ZERO!
# was: eta = [0, 0, (i - 5) * 20, (5 - i) * 20, 0, 0], now is:
eta = [0.1, 0.1, (i - 5) * 20, (5 - i) * 20, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
- traj = eta3_trajectory(trajectory_segments,
- max_vel=max_vel, max_accel=0.5)
+ traj = Eta3SplineTrajectory(trajectory_segments,
+ max_vel=max_vel, max_accel=0.5)
# interpolate at several points along the path
times = np.linspace(0, traj.total_time, 101)
@@ -366,7 +362,7 @@ def test3(max_vel=2.0):
# NOTE: The ordering on kappa is [kappa_A, kappad_A, kappa_B, kappad_B], with kappad_* being the curvature derivative
kappa = [0, 0, 0, 0]
eta = [4.27, 4.27, 0, 0, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 2: line segment
@@ -376,7 +372,7 @@ def test3(max_vel=2.0):
# NOTE: INTEGRATOR ERROR EXPLODES WHEN eta[:1] IS ZERO!
# was: eta = [0, 0, 0, 0, 0, 0], now is:
eta = [0.5, 0.5, 0, 0, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 3: cubic spiral
@@ -384,7 +380,7 @@ def test3(max_vel=2.0):
end_pose = [7.4377, 1.8235, 0.6667]
kappa = [0, 0, 1, 1]
eta = [1.88, 1.88, 0, 0, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 4: generic twirl arc
@@ -392,7 +388,7 @@ def test3(max_vel=2.0):
end_pose = [7.8, 4.3, 1.8]
kappa = [1, 1, 0.5, 0]
eta = [7, 10, 10, -10, 4, 4]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# segment 5: circular arc
@@ -400,12 +396,12 @@ def test3(max_vel=2.0):
end_pose = [5.4581, 5.8064, 3.3416]
kappa = [0.5, 0, 0.5, 0]
eta = [2.98, 2.98, 0, 0, 0, 0]
- trajectory_segments.append(eta3_path_segment(
+ trajectory_segments.append(Eta3PathSegment(
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
# construct the whole path
- traj = eta3_trajectory(trajectory_segments,
- max_vel=max_vel, max_accel=0.5, max_jerk=1)
+ traj = Eta3SplineTrajectory(trajectory_segments,
+ max_vel=max_vel, max_accel=0.5, max_jerk=1)
# interpolate at several points along the path
times = np.linspace(0, traj.total_time, 1001)
diff --git a/PathPlanning/FlowField/flowfield.py b/PathPlanning/FlowField/flowfield.py
new file mode 100644
index 0000000000..e50430de3c
--- /dev/null
+++ b/PathPlanning/FlowField/flowfield.py
@@ -0,0 +1,227 @@
+"""
+flowfield pathfinding
+author: Sarim Mehdi (muhammadsarim.mehdi@studio.unibo.it)
+Source: https://leifnode.com/2013/12/flow-field-pathfinding/
+"""
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+def draw_horizontal_line(start_x, start_y, length, o_x, o_y, o_dict, path):
+ for i in range(start_x, start_x + length):
+ for j in range(start_y, start_y + 2):
+ o_x.append(i)
+ o_y.append(j)
+ o_dict[(i, j)] = path
+
+
+def draw_vertical_line(start_x, start_y, length, o_x, o_y, o_dict, path):
+ for i in range(start_x, start_x + 2):
+ for j in range(start_y, start_y + length):
+ o_x.append(i)
+ o_y.append(j)
+ o_dict[(i, j)] = path
+
+
+class FlowField:
+ def __init__(self, obs_grid, goal_x, goal_y, start_x, start_y,
+ limit_x, limit_y):
+ self.start_pt = [start_x, start_y]
+ self.goal_pt = [goal_x, goal_y]
+ self.obs_grid = obs_grid
+ self.limit_x, self.limit_y = limit_x, limit_y
+ self.cost_field = {}
+ self.integration_field = {}
+ self.vector_field = {}
+
+ def find_path(self):
+ self.create_cost_field()
+ self.create_integration_field()
+ self.assign_vectors()
+ self.follow_vectors()
+
+ def create_cost_field(self):
+ """Assign cost to each grid which defines the energy
+ it would take to get there."""
+ for i in range(self.limit_x):
+ for j in range(self.limit_y):
+ if self.obs_grid[(i, j)] == 'free':
+ self.cost_field[(i, j)] = 1
+ elif self.obs_grid[(i, j)] == 'medium':
+ self.cost_field[(i, j)] = 7
+ elif self.obs_grid[(i, j)] == 'hard':
+ self.cost_field[(i, j)] = 20
+ elif self.obs_grid[(i, j)] == 'obs':
+ continue
+
+ if [i, j] == self.goal_pt:
+ self.cost_field[(i, j)] = 0
+
+ def create_integration_field(self):
+ """Start from the goal node and calculate the value
+ of the integration field at each node. Start by
+ assigning a value of infinity to every node except
+ the goal node which is assigned a value of 0. Put the
+ goal node in the open list and then get its neighbors
+ (must not be obstacles). For each neighbor, the new
+ cost is equal to the cost of the current node in the
+ integration field (in the beginning, this will simply
+ be the goal node) + the cost of the neighbor in the
+ cost field + the extra cost (optional). The new cost
+ is only assigned if it is less than the previously
+ assigned cost of the node in the integration field and,
+ when that happens, the neighbor is put on the open list.
+ This process continues until the open list is empty."""
+ for i in range(self.limit_x):
+ for j in range(self.limit_y):
+ if self.obs_grid[(i, j)] == 'obs':
+ continue
+ self.integration_field[(i, j)] = np.inf
+ if [i, j] == self.goal_pt:
+ self.integration_field[(i, j)] = 0
+
+ open_list = [(self.goal_pt, 0)]
+ while open_list:
+ curr_pos, curr_cost = open_list[0]
+ curr_x, curr_y = curr_pos
+ for i in range(-1, 2):
+ for j in range(-1, 2):
+ x, y = curr_x + i, curr_y + j
+ if self.obs_grid[(x, y)] == 'obs':
+ continue
+ if (i, j) in [(1, 0), (0, 1), (-1, 0), (0, -1)]:
+ e_cost = 10
+ else:
+ e_cost = 14
+ neighbor_energy = self.cost_field[(x, y)]
+ neighbor_old_cost = self.integration_field[(x, y)]
+ neighbor_new_cost = curr_cost + neighbor_energy + e_cost
+ if neighbor_new_cost < neighbor_old_cost:
+ self.integration_field[(x, y)] = neighbor_new_cost
+ open_list.append(([x, y], neighbor_new_cost))
+ del open_list[0]
+
+ def assign_vectors(self):
+ """For each node, assign a vector from itself to the node with
+ the lowest cost in the integration field. An agent will simply
+ follow this vector field to the goal"""
+ for i in range(self.limit_x):
+ for j in range(self.limit_y):
+ if self.obs_grid[(i, j)] == 'obs':
+ continue
+ if [i, j] == self.goal_pt:
+ self.vector_field[(i, j)] = (None, None)
+ continue
+ offset_list = [(i + a, j + b)
+ for a in range(-1, 2)
+ for b in range(-1, 2)]
+ neighbor_list = [{'loc': pt,
+ 'cost': self.integration_field[pt]}
+ for pt in offset_list
+ if self.obs_grid[pt] != 'obs']
+ neighbor_list = sorted(neighbor_list, key=lambda x: x['cost'])
+ best_neighbor = neighbor_list[0]['loc']
+ self.vector_field[(i, j)] = best_neighbor
+
+ def follow_vectors(self):
+ curr_x, curr_y = self.start_pt
+ while curr_x is not None and curr_y is not None:
+ curr_x, curr_y = self.vector_field[(curr_x, curr_y)]
+
+ if show_animation:
+ plt.plot(curr_x, curr_y, "b*")
+ plt.pause(0.001)
+
+ if show_animation:
+ plt.show()
+
+
+def main():
+ # set obstacle positions
+ obs_dict = {}
+ for i in range(51):
+ for j in range(51):
+ obs_dict[(i, j)] = 'free'
+ o_x, o_y, m_x, m_y, h_x, h_y = [], [], [], [], [], []
+
+ s_x = 5.0
+ s_y = 5.0
+ g_x = 35.0
+ g_y = 45.0
+
+ # draw outer border of maze
+ draw_vertical_line(0, 0, 50, o_x, o_y, obs_dict, 'obs')
+ draw_vertical_line(48, 0, 50, o_x, o_y, obs_dict, 'obs')
+ draw_horizontal_line(0, 0, 50, o_x, o_y, obs_dict, 'obs')
+ draw_horizontal_line(0, 48, 50, o_x, o_y, obs_dict, 'obs')
+
+ # draw inner walls
+ all_x = [10, 10, 10, 15, 20, 20, 30, 30, 35, 30, 40, 45]
+ all_y = [10, 30, 45, 20, 5, 40, 10, 40, 5, 40, 10, 25]
+ all_len = [10, 10, 5, 10, 10, 5, 20, 10, 25, 10, 35, 15]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_vertical_line(x, y, l, o_x, o_y, obs_dict, 'obs')
+
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [35, 40, 15, 10, 45, 20, 10, 15, 25, 45, 10, 30, 10, 40]
+ all_y = [5, 10, 15, 20, 20, 25, 30, 35, 35, 35, 40, 40, 45, 45]
+ all_len = [10, 5, 10, 10, 5, 5, 10, 5, 10, 5, 10, 5, 5, 5]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_horizontal_line(x, y, l, o_x, o_y, obs_dict, 'obs')
+
+ # Some points are assigned a slightly higher energy value in the cost
+ # field. For example, if an agent wishes to go to a point, it might
+ # encounter different kind of terrain like grass and dirt. Grass is
+ # assigned medium difficulty of passage (color coded as green on the
+ # map here). Dirt is assigned hard difficulty of passage (color coded
+ # as brown here). Hence, this algorithm will take into account how
+ # difficult it is to go through certain areas of a map when deciding
+ # the shortest path.
+
+ # draw paths that have medium difficulty (in terms of going through them)
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [10, 45]
+ all_y = [22, 20]
+ all_len = [8, 5]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_vertical_line(x, y, l, m_x, m_y, obs_dict, 'medium')
+
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [20, 30, 42] + [47] * 5
+ all_y = [35, 30, 38] + [37 + i for i in range(2)]
+ all_len = [5, 7, 3] + [1] * 3
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_horizontal_line(x, y, l, m_x, m_y, obs_dict, 'medium')
+
+ # draw paths that have hard difficulty (in terms of going through them)
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [15, 20, 35]
+ all_y = [45, 20, 35]
+ all_len = [3, 5, 7]
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_vertical_line(x, y, l, h_x, h_y, obs_dict, 'hard')
+
+ all_x[:], all_y[:], all_len[:] = [], [], []
+ all_x = [30] + [47] * 5
+ all_y = [10] + [37 + i for i in range(2)]
+ all_len = [5] + [1] * 3
+ for x, y, l in zip(all_x, all_y, all_len):
+ draw_horizontal_line(x, y, l, h_x, h_y, obs_dict, 'hard')
+
+ if show_animation:
+ plt.plot(o_x, o_y, "sr")
+ plt.plot(m_x, m_y, "sg")
+ plt.plot(h_x, h_y, "sy")
+ plt.plot(s_x, s_y, "og")
+ plt.plot(g_x, g_y, "o")
+ plt.grid(True)
+
+ flow_obj = FlowField(obs_dict, g_x, g_y, s_x, s_y, 50, 50)
+ flow_obj.find_path()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py
new file mode 100644
index 0000000000..482712ceaf
--- /dev/null
+++ b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py
@@ -0,0 +1,144 @@
+"""
+
+A converter between Cartesian and Frenet coordinate systems
+
+author: Wang Zheng (@Aglargil)
+
+Reference:
+
+- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame]
+(https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf)
+
+"""
+
+import math
+
+
+class CartesianFrenetConverter:
+ """
+ A class for converting states between Cartesian and Frenet coordinate systems
+ """
+
+ @ staticmethod
+ def cartesian_to_frenet(rs, rx, ry, rtheta, rkappa, rdkappa, x, y, v, a, theta, kappa):
+ """
+ Convert state from Cartesian coordinate to Frenet coordinate
+
+ Parameters
+ ----------
+ rs: reference line s-coordinate
+ rx, ry: reference point coordinates
+ rtheta: reference point heading
+ rkappa: reference point curvature
+ rdkappa: reference point curvature rate
+ x, y: current position
+ v: velocity
+ a: acceleration
+ theta: heading angle
+ kappa: curvature
+
+ Returns
+ -------
+ s_condition: [s(t), s'(t), s''(t)]
+ d_condition: [d(s), d'(s), d''(s)]
+ """
+ dx = x - rx
+ dy = y - ry
+
+ cos_theta_r = math.cos(rtheta)
+ sin_theta_r = math.sin(rtheta)
+
+ cross_rd_nd = cos_theta_r * dy - sin_theta_r * dx
+ d = math.copysign(math.hypot(dx, dy), cross_rd_nd)
+
+ delta_theta = theta - rtheta
+ tan_delta_theta = math.tan(delta_theta)
+ cos_delta_theta = math.cos(delta_theta)
+
+ one_minus_kappa_r_d = 1 - rkappa * d
+ d_dot = one_minus_kappa_r_d * tan_delta_theta
+
+ kappa_r_d_prime = rdkappa * d + rkappa * d_dot
+
+ d_ddot = (-kappa_r_d_prime * tan_delta_theta +
+ one_minus_kappa_r_d / (cos_delta_theta * cos_delta_theta) *
+ (kappa * one_minus_kappa_r_d / cos_delta_theta - rkappa))
+
+ s = rs
+ s_dot = v * cos_delta_theta / one_minus_kappa_r_d
+
+ delta_theta_prime = one_minus_kappa_r_d / cos_delta_theta * kappa - rkappa
+ s_ddot = (a * cos_delta_theta -
+ s_dot * s_dot *
+ (d_dot * delta_theta_prime - kappa_r_d_prime)) / one_minus_kappa_r_d
+
+ return [s, s_dot, s_ddot], [d, d_dot, d_ddot]
+
+ @ staticmethod
+ def frenet_to_cartesian(rs, rx, ry, rtheta, rkappa, rdkappa, s_condition, d_condition):
+ """
+ Convert state from Frenet coordinate to Cartesian coordinate
+
+ Parameters
+ ----------
+ rs: reference line s-coordinate
+ rx, ry: reference point coordinates
+ rtheta: reference point heading
+ rkappa: reference point curvature
+ rdkappa: reference point curvature rate
+ s_condition: [s(t), s'(t), s''(t)]
+ d_condition: [d(s), d'(s), d''(s)]
+
+ Returns
+ -------
+ x, y: position
+ theta: heading angle
+ kappa: curvature
+ v: velocity
+ a: acceleration
+ """
+ if abs(rs - s_condition[0]) >= 1.0e-6:
+ raise ValueError(
+ "The reference point s and s_condition[0] don't match")
+
+ cos_theta_r = math.cos(rtheta)
+ sin_theta_r = math.sin(rtheta)
+
+ x = rx - sin_theta_r * d_condition[0]
+ y = ry + cos_theta_r * d_condition[0]
+
+ one_minus_kappa_r_d = 1 - rkappa * d_condition[0]
+
+ tan_delta_theta = d_condition[1] / one_minus_kappa_r_d
+ delta_theta = math.atan2(d_condition[1], one_minus_kappa_r_d)
+ cos_delta_theta = math.cos(delta_theta)
+
+ theta = CartesianFrenetConverter.normalize_angle(delta_theta + rtheta)
+
+ kappa_r_d_prime = rdkappa * d_condition[0] + rkappa * d_condition[1]
+
+ kappa = (((d_condition[2] + kappa_r_d_prime * tan_delta_theta) *
+ cos_delta_theta * cos_delta_theta) / one_minus_kappa_r_d + rkappa) * \
+ cos_delta_theta / one_minus_kappa_r_d
+
+ d_dot = d_condition[1] * s_condition[1]
+ v = math.sqrt(one_minus_kappa_r_d * one_minus_kappa_r_d *
+ s_condition[1] * s_condition[1] + d_dot * d_dot)
+
+ delta_theta_prime = one_minus_kappa_r_d / cos_delta_theta * kappa - rkappa
+
+ a = (s_condition[2] * one_minus_kappa_r_d / cos_delta_theta +
+ s_condition[1] * s_condition[1] / cos_delta_theta *
+ (d_condition[1] * delta_theta_prime - kappa_r_d_prime))
+
+ return x, y, theta, kappa, v, a
+
+ @ staticmethod
+ def normalize_angle(angle):
+ """
+ Normalize angle to [-pi, pi]
+ """
+ a = math.fmod(angle + math.pi, 2.0 * math.pi)
+ if a < 0.0:
+ a += 2.0 * math.pi
+ return a - math.pi
diff --git a/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py b/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py
deleted file mode 100644
index 98ef8c4ecf..0000000000
--- a/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py
+++ /dev/null
@@ -1,239 +0,0 @@
-"""
-cubic spline planner
-
-Author: Atsushi Sakai
-
-"""
-import math
-import numpy as np
-import bisect
-
-
-class Spline:
- """
- Cubic Spline class
- """
-
- def __init__(self, x, y):
- self.b, self.c, self.d, self.w = [], [], [], []
-
- self.x = x
- self.y = y
-
- self.nx = len(x) # dimension of x
- h = np.diff(x)
-
- # calc coefficient c
- self.a = [iy for iy in y]
-
- # calc coefficient c
- A = self.__calc_A(h)
- B = self.__calc_B(h)
- self.c = np.linalg.solve(A, B)
- # print(self.c1)
-
- # calc spline coefficient b and d
- for i in range(self.nx - 1):
- self.d.append((self.c[i + 1] - self.c[i]) / (3.0 * h[i]))
- tb = (self.a[i + 1] - self.a[i]) / h[i] - h[i] * \
- (self.c[i + 1] + 2.0 * self.c[i]) / 3.0
- self.b.append(tb)
-
- def calc(self, t):
- """
- Calc position
-
- if t is outside of the input x, return None
-
- """
-
- if t < self.x[0]:
- return None
- elif t > self.x[-1]:
- return None
-
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = self.a[i] + self.b[i] * dx + \
- self.c[i] * dx ** 2.0 + self.d[i] * dx ** 3.0
-
- return result
-
- def calcd(self, t):
- """
- Calc first derivative
-
- if t is outside of the input x, return None
- """
-
- if t < self.x[0]:
- return None
- elif t > self.x[-1]:
- return None
-
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = self.b[i] + 2.0 * self.c[i] * dx + 3.0 * self.d[i] * dx ** 2.0
- return result
-
- def calcdd(self, t):
- """
- Calc second derivative
- """
-
- if t < self.x[0]:
- return None
- elif t > self.x[-1]:
- return None
-
- i = self.__search_index(t)
- dx = t - self.x[i]
- result = 2.0 * self.c[i] + 6.0 * self.d[i] * dx
- return result
-
- def __search_index(self, x):
- """
- search data segment index
- """
- return bisect.bisect(self.x, x) - 1
-
- def __calc_A(self, h):
- """
- calc matrix A for spline coefficient c
- """
- A = np.zeros((self.nx, self.nx))
- A[0, 0] = 1.0
- for i in range(self.nx - 1):
- if i != (self.nx - 2):
- A[i + 1, i + 1] = 2.0 * (h[i] + h[i + 1])
- A[i + 1, i] = h[i]
- A[i, i + 1] = h[i]
-
- A[0, 1] = 0.0
- A[self.nx - 1, self.nx - 2] = 0.0
- A[self.nx - 1, self.nx - 1] = 1.0
- # print(A)
- return A
-
- def __calc_B(self, h):
- """
- calc matrix B for spline coefficient c
- """
- B = np.zeros(self.nx)
- for i in range(self.nx - 2):
- B[i + 1] = 3.0 * (self.a[i + 2] - self.a[i + 1]) / \
- h[i + 1] - 3.0 * (self.a[i + 1] - self.a[i]) / h[i]
- # print(B)
- return B
-
-
-class Spline2D:
- """
- 2D Cubic Spline class
-
- """
-
- def __init__(self, x, y):
- self.s = self.__calc_s(x, y)
- self.sx = Spline(self.s, x)
- self.sy = Spline(self.s, y)
-
- def __calc_s(self, x, y):
- dx = np.diff(x)
- dy = np.diff(y)
- self.ds = [math.sqrt(idx ** 2 + idy ** 2)
- for (idx, idy) in zip(dx, dy)]
- s = [0]
- s.extend(np.cumsum(self.ds))
- return s
-
- def calc_position(self, s):
- """
- calc position
- """
- x = self.sx.calc(s)
- y = self.sy.calc(s)
-
- return x, y
-
- def calc_curvature(self, s):
- """
- calc curvature
- """
- dx = self.sx.calcd(s)
- ddx = self.sx.calcdd(s)
- dy = self.sy.calcd(s)
- ddy = self.sy.calcdd(s)
- k = (ddy * dx - ddx * dy) / (dx ** 2 + dy ** 2)
- return k
-
- def calc_yaw(self, s):
- """
- calc yaw
- """
- dx = self.sx.calcd(s)
- dy = self.sy.calcd(s)
- yaw = math.atan2(dy, dx)
- return yaw
-
-
-def calc_spline_course(x, y, ds=0.1):
- sp = Spline2D(x, y)
- s = list(np.arange(0, sp.s[-1], ds))
-
- rx, ry, ryaw, rk = [], [], [], []
- for i_s in s:
- ix, iy = sp.calc_position(i_s)
- rx.append(ix)
- ry.append(iy)
- ryaw.append(sp.calc_yaw(i_s))
- rk.append(sp.calc_curvature(i_s))
-
- return rx, ry, ryaw, rk, s
-
-
-def main(): # pragma: no cover
- print("Spline 2D test")
- import matplotlib.pyplot as plt
- x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0]
- y = [0.7, -6, 5, 6.5, 0.0, 5.0, -2.0]
-
- sp = Spline2D(x, y)
- s = np.arange(0, sp.s[-1], 0.1)
-
- rx, ry, ryaw, rk = [], [], [], []
- for i_s in s:
- ix, iy = sp.calc_position(i_s)
- rx.append(ix)
- ry.append(iy)
- ryaw.append(sp.calc_yaw(i_s))
- rk.append(sp.calc_curvature(i_s))
-
- plt.subplots(1)
- plt.plot(x, y, "xb", label="input")
- plt.plot(rx, ry, "-r", label="spline")
- plt.grid(True)
- plt.axis("equal")
- plt.xlabel("x[m]")
- plt.ylabel("y[m]")
- plt.legend()
-
- plt.subplots(1)
- plt.plot(s, [np.rad2deg(iyaw) for iyaw in ryaw], "-r", label="yaw")
- plt.grid(True)
- plt.legend()
- plt.xlabel("line length[m]")
- plt.ylabel("yaw angle[deg]")
-
- plt.subplots(1)
- plt.plot(s, rk, "-r", label="curvature")
- plt.grid(True)
- plt.legend()
- plt.xlabel("line length[m]")
- plt.ylabel("curvature [1/m]")
-
- plt.show()
-
-
-if __name__ == '__main__': # pragma: no cover
- main()
diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py
index 5c756a9dfe..4b82fb70fd 100644
--- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py
+++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py
@@ -4,130 +4,348 @@
author: Atsushi Sakai (@Atsushi_twi)
-Ref:
+Reference:
-- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame](https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf)
+- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame]
+(https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf)
-- [Optimal trajectory generation for dynamic street scenarios in a Frenet Frame](https://www.youtube.com/watch?v=Cj6tAQe7UCY)
+- [Optimal trajectory generation for dynamic street scenarios in a Frenet Frame]
+(https://www.youtube.com/watch?v=Cj6tAQe7UCY)
"""
import numpy as np
import matplotlib.pyplot as plt
import copy
-import math
-import cubic_spline_planner
+import sys
+import pathlib
-SIM_LOOP = 500
-
-# Parameter
-MAX_SPEED = 50.0 / 3.6 # maximum speed [m/s]
-MAX_ACCEL = 2.0 # maximum acceleration [m/ss]
-MAX_CURVATURE = 1.0 # maximum curvature [1/m]
-MAX_ROAD_WIDTH = 7.0 # maximum road width [m]
-D_ROAD_W = 1.0 # road width sampling length [m]
-DT = 0.2 # time tick [s]
-MAXT = 5.0 # max prediction time [m]
-MINT = 4.0 # min prediction time [m]
-TARGET_SPEED = 30.0 / 3.6 # target speed [m/s]
-D_T_S = 5.0 / 3.6 # target speed sampling length [m/s]
-N_S_SAMPLE = 1 # sampling number of target speed
-ROBOT_RADIUS = 2.0 # robot radius [m]
-
-# cost weights
-KJ = 0.1
-KT = 0.1
-KD = 1.0
-KLAT = 1.0
-KLON = 1.0
-
-show_animation = True
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+from QuinticPolynomialsPlanner.quintic_polynomials_planner import QuinticPolynomial
+from CubicSpline import cubic_spline_planner
-class quintic_polynomial:
-
- def __init__(self, xs, vxs, axs, xe, vxe, axe, T):
-
- # calc coefficient of quintic polynomial
- self.xs = xs
- self.vxs = vxs
- self.axs = axs
- self.xe = xe
- self.vxe = vxe
- self.axe = axe
-
- self.a0 = xs
- self.a1 = vxs
- self.a2 = axs / 2.0
-
- A = np.array([[T**3, T**4, T**5],
- [3 * T ** 2, 4 * T ** 3, 5 * T ** 4],
- [6 * T, 12 * T ** 2, 20 * T ** 3]])
- b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2,
- vxe - self.a1 - 2 * self.a2 * T,
- axe - 2 * self.a2])
- x = np.linalg.solve(A, b)
-
- self.a3 = x[0]
- self.a4 = x[1]
- self.a5 = x[2]
+from enum import Enum, auto
+from FrenetOptimalTrajectory.cartesian_frenet_converter import (
+ CartesianFrenetConverter,
+)
- def calc_point(self, t):
- xt = self.a0 + self.a1 * t + self.a2 * t**2 + \
- self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5
- return xt
+class LateralMovement(Enum):
+ HIGH_SPEED = auto()
+ LOW_SPEED = auto()
- def calc_first_derivative(self, t):
- xt = self.a1 + 2 * self.a2 * t + \
- 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4
- return xt
+class LongitudinalMovement(Enum):
+ MERGING_AND_STOPPING = auto()
+ VELOCITY_KEEPING = auto()
- def calc_second_derivative(self, t):
- xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3
- return xt
+# Default Parameters
- def calc_third_derivative(self, t):
- xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2
+LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED
+LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING
- return xt
+MAX_SPEED = 50.0 / 3.6 # maximum speed [m/s]
+MAX_ACCEL = 5.0 # maximum acceleration [m/ss]
+MAX_CURVATURE = 1.0 # maximum curvature [1/m]
+DT = 0.2 # time tick [s]
+MAX_T = 5.0 # max prediction time [m]
+MIN_T = 4.0 # min prediction time [m]
+N_S_SAMPLE = 1 # sampling number of target speed
+# cost weights
+K_J = 0.1
+K_T = 0.1
+K_S_DOT = 1.0
+K_D = 1.0
+K_S = 1.0
+K_LAT = 1.0
+K_LON = 1.0
-class quartic_polynomial:
+SIM_LOOP = 500
+show_animation = True
- def __init__(self, xs, vxs, axs, vxe, axe, T):
- # calc coefficient of quintic polynomial
- self.xs = xs
- self.vxs = vxs
- self.axs = axs
- self.vxe = vxe
- self.axe = axe
+if LATERAL_MOVEMENT == LateralMovement.LOW_SPEED:
+ MAX_ROAD_WIDTH = 1.0 # maximum road width [m]
+ D_ROAD_W = 0.2 # road width sampling length [m]
+ TARGET_SPEED = 3.0 / 3.6 # maximum speed [m/s]
+ D_T_S = 0.5 / 3.6 # target speed sampling length [m/s]
+ # Waypoints
+ WX = [0.0, 2.0, 4.0, 6.0, 8.0, 10.0]
+ WY = [0.0, 0.0, 1.0, 0.0, -1.0, -2.0]
+ OBSTACLES = np.array([[3.0, 1.0], [5.0, -0.0], [6.0, 0.5], [8.0, -1.5]])
+ ROBOT_RADIUS = 0.5 # robot radius [m]
+
+ # Initial state parameters
+ INITIAL_SPEED = 1.0 / 3.6 # current speed [m/s]
+ INITIAL_ACCEL = 0.0 # current acceleration [m/ss]
+ INITIAL_LAT_POSITION = 0.5 # current lateral position [m]
+ INITIAL_LAT_SPEED = 0.0 # current lateral speed [m/s]
+ INITIAL_LAT_ACCELERATION = 0.0 # current lateral acceleration [m/s]
+ INITIAL_COURSE_POSITION = 0.0 # current course position
+
+ ANIMATION_AREA = 5.0 # Animation area length [m]
+
+ STOP_S = 4.0 # Merge and stop distance [m]
+ D_S = 0.3 # Stop point sampling length [m]
+ N_STOP_S_SAMPLE = 3 # Stop point sampling number
+else:
+ MAX_ROAD_WIDTH = 7.0 # maximum road width [m]
+ D_ROAD_W = 1.0 # road width sampling length [m]
+ TARGET_SPEED = 30.0 / 3.6 # target speed [m/s]
+ D_T_S = 5.0 / 3.6 # target speed sampling length [m/s]
+ # Waypoints
+ WX = [0.0, 10.0, 20.5, 35.0, 70.5]
+ WY = [0.0, -6.0, 5.0, 6.5, 0.0]
+ # Obstacle list
+ OBSTACLES = np.array(
+ [[20.0, 10.0], [30.0, 6.0], [30.0, 8.0], [35.0, 8.0], [50.0, 3.0]]
+ )
+ ROBOT_RADIUS = 2.0 # robot radius [m]
+
+ # Initial state parameters
+ INITIAL_SPEED = 10.0 / 3.6 # current speed [m/s]
+ INITIAL_ACCEL = 0.0 # current acceleration [m/ss]
+ INITIAL_LAT_POSITION = 2.0 # current lateral position [m]
+ INITIAL_LAT_SPEED = 0.0 # current lateral speed [m/s]
+ INITIAL_LAT_ACCELERATION = 0.0 # current lateral acceleration [m/s]
+ INITIAL_COURSE_POSITION = 0.0 # current course position
+
+ ANIMATION_AREA = 20.0 # Animation area length [m]
+ STOP_S = 25.0 # Merge and stop distance [m]
+ D_S = 2 # Stop point sampling length [m]
+ N_STOP_S_SAMPLE = 4 # Stop point sampling number
+
+
+class LateralMovementStrategy:
+ def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti):
+ """
+ Calculate the lateral trajectory
+ """
+ raise NotImplementedError("calc_lateral_trajectory not implemented")
+
+ def calc_cartesian_parameters(self, fp, csp):
+ """
+ Calculate the cartesian parameters (x, y, yaw, curvature, v, a)
+ """
+ raise NotImplementedError("calc_cartesian_parameters not implemented")
+
+
+class HighSpeedLateralMovementStrategy(LateralMovementStrategy):
+ def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti):
+ tp = copy.deepcopy(fp)
+ s0_d = fp.s_d[0]
+ s0_dd = fp.s_dd[0]
+ # d'(t) = d'(s) * s'(t)
+ # d''(t) = d''(s) * s'(t)^2 + d'(s) * s''(t)
+ lat_qp = QuinticPolynomial(
+ c_d, c_d_d * s0_d, c_d_dd * s0_d**2 + c_d_d * s0_dd, di, 0.0, 0.0, Ti
+ )
+
+ tp.d = []
+ tp.d_d = []
+ tp.d_dd = []
+ tp.d_ddd = []
+
+ # Calculate all derivatives in a single loop to reduce iterations
+ for i in range(len(fp.t)):
+ t = fp.t[i]
+ s_d = fp.s_d[i]
+ s_dd = fp.s_dd[i]
+
+ s_d_inv = 1.0 / (s_d + 1e-6) + 1e-6 # Avoid division by zero
+ s_d_inv_sq = s_d_inv * s_d_inv # Square of inverse
+
+ d = lat_qp.calc_point(t)
+ d_d = lat_qp.calc_first_derivative(t)
+ d_dd = lat_qp.calc_second_derivative(t)
+ d_ddd = lat_qp.calc_third_derivative(t)
+
+ tp.d.append(d)
+ # d'(s) = d'(t) / s'(t)
+ tp.d_d.append(d_d * s_d_inv)
+ # d''(s) = (d''(t) - d'(s) * s''(t)) / s'(t)^2
+ tp.d_dd.append((d_dd - tp.d_d[i] * s_dd) * s_d_inv_sq)
+ tp.d_ddd.append(d_ddd)
+
+ return tp
+
+ def calc_cartesian_parameters(self, fp, csp):
+ # calc global positions
+ for i in range(len(fp.s)):
+ ix, iy = csp.calc_position(fp.s[i])
+ if ix is None:
+ break
+ i_yaw = csp.calc_yaw(fp.s[i])
+ i_kappa = csp.calc_curvature(fp.s[i])
+ i_dkappa = csp.calc_curvature_rate(fp.s[i])
+ s_condition = [fp.s[i], fp.s_d[i], fp.s_dd[i]]
+ d_condition = [
+ fp.d[i],
+ fp.d_d[i],
+ fp.d_dd[i],
+ ]
+ x, y, theta, kappa, v, a = CartesianFrenetConverter.frenet_to_cartesian(
+ fp.s[i], ix, iy, i_yaw, i_kappa, i_dkappa, s_condition, d_condition
+ )
+ fp.x.append(x)
+ fp.y.append(y)
+ fp.yaw.append(theta)
+ fp.c.append(kappa)
+ fp.v.append(v)
+ fp.a.append(a)
+ return fp
+
+
+class LowSpeedLateralMovementStrategy(LateralMovementStrategy):
+ def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti):
+ s0 = fp.s[0]
+ s1 = fp.s[-1]
+ tp = copy.deepcopy(fp)
+ # d = d(s), d_d = d'(s), d_dd = d''(s)
+ # * shift s range from [s0, s1] to [0, s1 - s0]
+ lat_qp = QuinticPolynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, s1 - s0)
+
+ tp.d = [lat_qp.calc_point(s - s0) for s in fp.s]
+ tp.d_d = [lat_qp.calc_first_derivative(s - s0) for s in fp.s]
+ tp.d_dd = [lat_qp.calc_second_derivative(s - s0) for s in fp.s]
+ tp.d_ddd = [lat_qp.calc_third_derivative(s - s0) for s in fp.s]
+ return tp
+
+ def calc_cartesian_parameters(self, fp, csp):
+ # calc global positions
+ for i in range(len(fp.s)):
+ ix, iy = csp.calc_position(fp.s[i])
+ if ix is None:
+ break
+ i_yaw = csp.calc_yaw(fp.s[i])
+ i_kappa = csp.calc_curvature(fp.s[i])
+ i_dkappa = csp.calc_curvature_rate(fp.s[i])
+ s_condition = [fp.s[i], fp.s_d[i], fp.s_dd[i]]
+ d_condition = [fp.d[i], fp.d_d[i], fp.d_dd[i]]
+ x, y, theta, kappa, v, a = CartesianFrenetConverter.frenet_to_cartesian(
+ fp.s[i], ix, iy, i_yaw, i_kappa, i_dkappa, s_condition, d_condition
+ )
+ fp.x.append(x)
+ fp.y.append(y)
+ fp.yaw.append(theta)
+ fp.c.append(kappa)
+ fp.v.append(v)
+ fp.a.append(a)
+ return fp
+
+
+class LongitudinalMovementStrategy:
+ def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0):
+ """
+ Calculate the longitudinal trajectory
+ """
+ raise NotImplementedError("calc_longitudinal_trajectory not implemented")
+
+ def get_d_arrange(self, s0):
+ """
+ Get the d sample range
+ """
+ raise NotImplementedError("get_d_arrange not implemented")
+
+ def calc_destination_cost(self, fp):
+ """
+ Calculate the destination cost
+ """
+ raise NotImplementedError("calc_destination_cost not implemented")
+
+
+class VelocityKeepingLongitudinalMovementStrategy(LongitudinalMovementStrategy):
+ def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0):
+ fplist = []
+ for tv in np.arange(
+ TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S
+ ):
+ fp = FrenetPath()
+ lon_qp = QuarticPolynomial(s0, c_speed, c_accel, tv, 0.0, Ti)
+ fp.t = [t for t in np.arange(0.0, Ti, DT)]
+ fp.s = [lon_qp.calc_point(t) for t in fp.t]
+ fp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t]
+ fp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t]
+ fp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t]
+ fplist.append(fp)
+ return fplist
+
+ def get_d_arrange(self, s0):
+ return np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W)
+
+ def calc_destination_cost(self, fp):
+ ds = (TARGET_SPEED - fp.s_d[-1]) ** 2
+ return K_S_DOT * ds
+
+
+class MergingAndStoppingLongitudinalMovementStrategy(LongitudinalMovementStrategy):
+ def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0):
+ if s0 >= STOP_S:
+ return []
+ fplist = []
+ for s in np.arange(
+ STOP_S - D_S * N_STOP_S_SAMPLE, STOP_S + D_S * N_STOP_S_SAMPLE, D_S
+ ):
+ fp = FrenetPath()
+ lon_qp = QuinticPolynomial(s0, c_speed, c_accel, s, 0.0, 0.0, Ti)
+ fp.t = [t for t in np.arange(0.0, Ti, DT)]
+ fp.s = [lon_qp.calc_point(t) for t in fp.t]
+ fp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t]
+ fp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t]
+ fp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t]
+ fplist.append(fp)
+ return fplist
+
+ def get_d_arrange(self, s0):
+ # Only if s0 is less than STOP_S / 3, then we sample the road width
+ if s0 < STOP_S / 3:
+ return np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W)
+ else:
+ return [0.0]
+
+ def calc_destination_cost(self, fp):
+ ds = (STOP_S - fp.s[-1]) ** 2
+ return K_S * ds
+
+LATERAL_MOVEMENT_STRATEGY: LateralMovementStrategy
+LONGITUDINAL_MOVEMENT_STRATEGY: LongitudinalMovementStrategy
+
+if LATERAL_MOVEMENT == LateralMovement.HIGH_SPEED:
+ LATERAL_MOVEMENT_STRATEGY = HighSpeedLateralMovementStrategy()
+else:
+ LATERAL_MOVEMENT_STRATEGY = LowSpeedLateralMovementStrategy()
+
+if LONGITUDINAL_MOVEMENT == LongitudinalMovement.VELOCITY_KEEPING:
+ LONGITUDINAL_MOVEMENT_STRATEGY = VelocityKeepingLongitudinalMovementStrategy()
+else:
+ LONGITUDINAL_MOVEMENT_STRATEGY = MergingAndStoppingLongitudinalMovementStrategy()
+
+
+class QuarticPolynomial:
+ def __init__(self, xs, vxs, axs, vxe, axe, time):
+ # calc coefficient of quartic polynomial
self.a0 = xs
self.a1 = vxs
self.a2 = axs / 2.0
- A = np.array([[3 * T ** 2, 4 * T ** 3],
- [6 * T, 12 * T ** 2]])
- b = np.array([vxe - self.a1 - 2 * self.a2 * T,
- axe - 2 * self.a2])
+ A = np.array([[3 * time**2, 4 * time**3], [6 * time, 12 * time**2]])
+ b = np.array([vxe - self.a1 - 2 * self.a2 * time, axe - 2 * self.a2])
x = np.linalg.solve(A, b)
self.a3 = x[0]
self.a4 = x[1]
def calc_point(self, t):
- xt = self.a0 + self.a1 * t + self.a2 * t**2 + \
- self.a3 * t**3 + self.a4 * t**4
+ xt = self.a0 + self.a1 * t + self.a2 * t**2 + self.a3 * t**3 + self.a4 * t**4
return xt
def calc_first_derivative(self, t):
- xt = self.a1 + 2 * self.a2 * t + \
- 3 * self.a3 * t**2 + 4 * self.a4 * t**3
+ xt = self.a1 + 2 * self.a2 * t + 3 * self.a3 * t**2 + 4 * self.a4 * t**3
return xt
@@ -142,111 +360,84 @@ def calc_third_derivative(self, t):
return xt
-class Frenet_path:
-
+class FrenetPath:
def __init__(self):
self.t = []
self.d = []
- self.d_d = []
- self.d_dd = []
- self.d_ddd = []
+ self.d_d = [] # d'(s)
+ self.d_dd = [] # d''(s)
+ self.d_ddd = [] # d'''(t) in low speed / d'''(s) in high speed
self.s = []
- self.s_d = []
- self.s_dd = []
- self.s_ddd = []
- self.cd = 0.0
- self.cv = 0.0
+ self.s_d = [] # s'(t)
+ self.s_dd = [] # s''(t)
+ self.s_ddd = [] # s'''(t)
self.cf = 0.0
self.x = []
self.y = []
self.yaw = []
+ self.v = []
+ self.a = []
self.ds = []
self.c = []
-
-def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0):
-
+ def pop_front(self):
+ self.x.pop(0)
+ self.y.pop(0)
+ self.yaw.pop(0)
+ self.v.pop(0)
+ self.a.pop(0)
+ self.s.pop(0)
+ self.s_d.pop(0)
+ self.s_dd.pop(0)
+ self.s_ddd.pop(0)
+ self.d.pop(0)
+ self.d_d.pop(0)
+ self.d_dd.pop(0)
+ self.d_ddd.pop(0)
+
+
+def calc_frenet_paths(c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, s0):
frenet_paths = []
- # generate path to each offset goal
- for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W):
-
- # Lateral motion planning
- for Ti in np.arange(MINT, MAXT, DT):
- fp = Frenet_path()
-
- lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti)
-
- fp.t = [t for t in np.arange(0.0, Ti, DT)]
- fp.d = [lat_qp.calc_point(t) for t in fp.t]
- fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t]
- fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t]
- fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t]
-
- # Loongitudinal motion planning (Velocity keeping)
- for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S):
- tfp = copy.deepcopy(fp)
- lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti)
-
- tfp.s = [lon_qp.calc_point(t) for t in fp.t]
- tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t]
- tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t]
- tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t]
-
- Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk
- Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk
-
- # square of diff from target speed
- ds = (TARGET_SPEED - tfp.s_d[-1])**2
-
- tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2
- tfp.cv = KJ * Js + KT * Ti + KD * ds
- tfp.cf = KLAT * tfp.cd + KLON * tfp.cv
-
- frenet_paths.append(tfp)
+ for Ti in np.arange(MIN_T, MAX_T, DT):
+ lon_paths = LONGITUDINAL_MOVEMENT_STRATEGY.calc_longitudinal_trajectory(
+ c_s_d, c_s_dd, Ti, s0
+ )
+
+ for fp in lon_paths:
+ for di in LONGITUDINAL_MOVEMENT_STRATEGY.get_d_arrange(s0):
+ tp = LATERAL_MOVEMENT_STRATEGY.calc_lateral_trajectory(
+ fp, di, c_d, c_d_d, c_d_dd, Ti
+ )
+
+ Jp = sum(np.power(tp.d_ddd, 2)) # square of jerk
+ Js = sum(np.power(tp.s_ddd, 2)) # square of jerk
+
+ lat_cost = K_J * Jp + K_T * Ti + K_D * tp.d[-1] ** 2
+ lon_cost = (
+ K_J * Js
+ + K_T * Ti
+ + LONGITUDINAL_MOVEMENT_STRATEGY.calc_destination_cost(tp)
+ )
+ tp.cf = K_LAT * lat_cost + K_LON * lon_cost
+ frenet_paths.append(tp)
return frenet_paths
def calc_global_paths(fplist, csp):
-
- for fp in fplist:
-
- # calc global positions
- for i in range(len(fp.s)):
- ix, iy = csp.calc_position(fp.s[i])
- if ix is None:
- break
- iyaw = csp.calc_yaw(fp.s[i])
- di = fp.d[i]
- fx = ix + di * math.cos(iyaw + math.pi / 2.0)
- fy = iy + di * math.sin(iyaw + math.pi / 2.0)
- fp.x.append(fx)
- fp.y.append(fy)
-
- # calc yaw and ds
- for i in range(len(fp.x) - 1):
- dx = fp.x[i + 1] - fp.x[i]
- dy = fp.y[i + 1] - fp.y[i]
- fp.yaw.append(math.atan2(dy, dx))
- fp.ds.append(math.sqrt(dx**2 + dy**2))
-
- fp.yaw.append(fp.yaw[-1])
- fp.ds.append(fp.ds[-1])
-
- # calc curvature
- for i in range(len(fp.yaw) - 1):
- fp.c.append((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i])
-
- return fplist
+ return [
+ LATERAL_MOVEMENT_STRATEGY.calc_cartesian_parameters(fp, csp) for fp in fplist
+ ]
def check_collision(fp, ob):
-
for i in range(len(ob[:, 0])):
- d = [((ix - ob[i, 0])**2 + (iy - ob[i, 1])**2)
- for (ix, iy) in zip(fp.x, fp.y)]
+ d = [
+ ((ix - ob[i, 0]) ** 2 + (iy - ob[i, 1]) ** 2)
+ for (ix, iy) in zip(fp.x, fp.y)
+ ]
collision = any([di <= ROBOT_RADIUS**2 for di in d])
@@ -257,42 +448,45 @@ def check_collision(fp, ob):
def check_paths(fplist, ob):
-
- okind = []
+ path_dict = {
+ "max_speed_error": [],
+ "max_accel_error": [],
+ "max_curvature_error": [],
+ "collision_error": [],
+ "ok": [],
+ }
for i, _ in enumerate(fplist):
- if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check
- continue
- elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check
- continue
+ if any([v > MAX_SPEED for v in fplist[i].v]): # Max speed check
+ path_dict["max_speed_error"].append(fplist[i])
+ elif any([abs(a) > MAX_ACCEL for a in fplist[i].a]): # Max accel check
+ path_dict["max_accel_error"].append(fplist[i])
elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check
- continue
+ path_dict["max_curvature_error"].append(fplist[i])
elif not check_collision(fplist[i], ob):
- continue
-
- okind.append(i)
+ path_dict["collision_error"].append(fplist[i])
+ else:
+ path_dict["ok"].append(fplist[i])
+ return path_dict
- return [fplist[i] for i in okind]
-
-def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob):
-
- fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0)
+def frenet_optimal_planning(csp, s0, c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, ob):
+ fplist = calc_frenet_paths(c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, s0)
fplist = calc_global_paths(fplist, csp)
- fplist = check_paths(fplist, ob)
+ fpdict = check_paths(fplist, ob)
# find minimum cost path
- mincost = float("inf")
- bestpath = None
- for fp in fplist:
- if mincost >= fp.cf:
- mincost = fp.cf
- bestpath = fp
+ min_cost = float("inf")
+ best_path = None
+ for fp in fpdict["ok"]:
+ if min_cost >= fp.cf:
+ min_cost = fp.cf
+ best_path = fp
- return bestpath
+ return [best_path, fpdict]
def generate_target_course(x, y):
- csp = cubic_spline_planner.Spline2D(x, y)
+ csp = cubic_spline_planner.CubicSpline2D(x, y)
s = np.arange(0, csp.s[-1], 0.1)
rx, ry, ryaw, rk = [], [], [], []
@@ -309,51 +503,57 @@ def generate_target_course(x, y):
def main():
print(__file__ + " start!!")
- # way points
- wx = [0.0, 10.0, 20.5, 35.0, 70.5]
- wy = [0.0, -6.0, 5.0, 6.5, 0.0]
- # obstacle lists
- ob = np.array([[20.0, 10.0],
- [30.0, 6.0],
- [30.0, 8.0],
- [35.0, 8.0],
- [50.0, 3.0]
- ])
+ tx, ty, tyaw, tc, csp = generate_target_course(WX, WY)
- tx, ty, tyaw, tc, csp = generate_target_course(wx, wy)
+ # Initialize state using global parameters
+ c_s_d = INITIAL_SPEED
+ c_s_dd = INITIAL_ACCEL
+ c_d = INITIAL_LAT_POSITION
+ c_d_d = INITIAL_LAT_SPEED
+ c_d_dd = INITIAL_LAT_ACCELERATION
+ s0 = INITIAL_COURSE_POSITION
- # initial state
- c_speed = 10.0 / 3.6 # current speed [m/s]
- c_d = 2.0 # current lateral position [m]
- c_d_d = 0.0 # current lateral speed [m/s]
- c_d_dd = 0.0 # current latral acceleration [m/s]
- s0 = 0.0 # current course position
+ area = ANIMATION_AREA
- area = 20.0 # animation area length [m]
+ last_path = None
for i in range(SIM_LOOP):
- path = frenet_optimal_planning(
- csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob)
+ [path, fpdict] = frenet_optimal_planning(
+ csp, s0, c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, OBSTACLES
+ )
+
+ if path is None:
+ path = copy.deepcopy(last_path)
+ path.pop_front()
+ if len(path.x) <= 1:
+ print("Finish")
+ break
+ last_path = path
s0 = path.s[1]
c_d = path.d[1]
c_d_d = path.d_d[1]
c_d_dd = path.d_dd[1]
- c_speed = path.s_d[1]
-
+ c_s_d = path.s_d[1]
+ c_s_dd = path.s_dd[1]
if np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0:
print("Goal")
break
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ "key_release_event",
+ lambda event: [exit(0) if event.key == "escape" else None],
+ )
plt.plot(tx, ty)
- plt.plot(ob[:, 0], ob[:, 1], "xk")
+ plt.plot(OBSTACLES[:, 0], OBSTACLES[:, 1], "xk")
plt.plot(path.x[1:], path.y[1:], "-or")
plt.plot(path.x[1], path.y[1], "vc")
plt.xlim(path.x[1] - area, path.x[1] + area)
plt.ylim(path.y[1] - area, path.y[1] + area)
- plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4])
+ plt.title("v[km/h]:" + str(path.v[1] * 3.6)[0:4])
plt.grid(True)
plt.pause(0.0001)
@@ -364,5 +564,5 @@ def main():
plt.show()
-if __name__ == '__main__':
+if __name__ == "__main__":
main()
diff --git a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py
new file mode 100644
index 0000000000..b259beb870
--- /dev/null
+++ b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py
@@ -0,0 +1,278 @@
+"""
+
+Greedy Best-First grid planning
+
+author: Erwin Lejeune (@spida_rwin)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/Best-first_search)
+
+"""
+
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = True
+
+
+class BestFirstSearchPlanner:
+
+ def __init__(self, ox, oy, reso, rr):
+ """
+ Initialize grid map for greedy best-first planning
+
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ self.reso = reso
+ self.rr = rr
+ self.calc_obstacle_map(ox, oy)
+ self.motion = self.get_motion_model()
+
+ class Node:
+ def __init__(self, x, y, cost, pind, parent):
+ self.x = x # index of grid
+ self.y = y # index of grid
+ self.cost = cost
+ self.pind = pind
+ self.parent = parent
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.pind)
+
+ def planning(self, sx, sy, gx, gy):
+ """
+ Greedy Best-First search
+
+ input:
+ s_x: start x position [m]
+ s_y: start y position [m]
+ gx: goal x position [m]
+ gy: goal y position [m]
+
+ output:
+ rx: x position list of the final path
+ ry: y position list of the final path
+ """
+
+ nstart = self.Node(self.calc_xyindex(sx, self.minx),
+ self.calc_xyindex(sy, self.miny), 0.0, -1, None)
+ ngoal = self.Node(self.calc_xyindex(gx, self.minx),
+ self.calc_xyindex(gy, self.miny), 0.0, -1, None)
+
+ open_set, closed_set = dict(), dict()
+ open_set[self.calc_grid_index(nstart)] = nstart
+
+ while True:
+ if len(open_set) == 0:
+ print("Open set is empty..")
+ break
+
+ c_id = min(
+ open_set,
+ key=lambda o: self.calc_heuristic(ngoal, open_set[o]))
+
+ current = open_set[c_id]
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(self.calc_grid_position(current.x, self.minx),
+ self.calc_grid_position(current.y, self.miny), "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event:
+ [exit(0)
+ if event.key == 'escape'
+ else None])
+ if len(closed_set.keys()) % 10 == 0:
+ plt.pause(0.001)
+
+ # Remove the item from the open set
+ del open_set[c_id]
+
+ # Add it to the closed set
+ closed_set[c_id] = current
+
+ if current.x == ngoal.x and current.y == ngoal.y:
+ print("Found goal")
+ ngoal.pind = current.pind
+ ngoal.cost = current.cost
+ break
+
+ # expand_grid search grid based on motion model
+ for i, _ in enumerate(self.motion):
+ node = self.Node(current.x + self.motion[i][0],
+ current.y + self.motion[i][1],
+ current.cost + self.motion[i][2],
+ c_id, current)
+
+ n_id = self.calc_grid_index(node)
+
+ # If the node is not safe, do nothing
+ if not self.verify_node(node):
+ continue
+
+ if n_id in closed_set:
+ continue
+
+ if n_id not in open_set:
+ open_set[n_id] = node
+ else:
+ if open_set[n_id].cost > node.cost:
+ open_set[n_id] = node
+ closed_set[ngoal.pind] = current
+ rx, ry = self.calc_final_path(ngoal, closed_set)
+ return rx, ry
+
+ def calc_final_path(self, ngoal, closedset):
+ # generate final course
+ rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [
+ self.calc_grid_position(ngoal.y, self.miny)]
+ n = closedset[ngoal.pind]
+ while n is not None:
+ rx.append(self.calc_grid_position(n.x, self.minx))
+ ry.append(self.calc_grid_position(n.y, self.miny))
+ n = n.parent
+
+ return rx, ry
+
+ @staticmethod
+ def calc_heuristic(n1, n2):
+ w = 1.0 # weight of heuristic
+ d = w * math.hypot(n1.x - n2.x, n1.y - n2.y)
+ return d
+
+ def calc_grid_position(self, index, minp):
+ """
+ calc grid position
+
+ :param index:
+ :param minp:
+ :return:
+ """
+ pos = index * self.reso + minp
+ return pos
+
+ def calc_xyindex(self, position, min_pos):
+ return round((position - min_pos) / self.reso)
+
+ def calc_grid_index(self, node):
+ return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
+
+ def verify_node(self, node):
+ px = self.calc_grid_position(node.x, self.minx)
+ py = self.calc_grid_position(node.y, self.miny)
+
+ if px < self.minx:
+ return False
+ elif py < self.miny:
+ return False
+ elif px >= self.maxx:
+ return False
+ elif py >= self.maxy:
+ return False
+
+ # collision check
+ if self.obmap[node.x][node.y]:
+ return False
+
+ return True
+
+ def calc_obstacle_map(self, ox, oy):
+
+ self.minx = round(min(ox))
+ self.miny = round(min(oy))
+ self.maxx = round(max(ox))
+ self.maxy = round(max(oy))
+ print("min_x:", self.minx)
+ print("min_y:", self.miny)
+ print("max_x:", self.maxx)
+ print("max_y:", self.maxy)
+
+ self.xwidth = round((self.maxx - self.minx) / self.reso)
+ self.ywidth = round((self.maxy - self.miny) / self.reso)
+ print("x_width:", self.xwidth)
+ print("y_width:", self.ywidth)
+
+ # obstacle map generation
+ self.obmap = [[False for _ in range(self.ywidth)]
+ for _ in range(self.xwidth)]
+ for ix in range(self.xwidth):
+ x = self.calc_grid_position(ix, self.minx)
+ for iy in range(self.ywidth):
+ y = self.calc_grid_position(iy, self.miny)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= self.rr:
+ self.obmap[ix][iy] = True
+ break
+
+ @staticmethod
+ def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx = 10.0 # [m]
+ sy = 10.0 # [m]
+ gx = 50.0 # [m]
+ gy = 50.0 # [m]
+ grid_size = 2.0 # [m]
+ robot_radius = 1.0 # [m]
+
+ # set obstacle positions
+ ox, oy = [], []
+ for i in range(-10, 60):
+ ox.append(i)
+ oy.append(-10.0)
+ for i in range(-10, 60):
+ ox.append(60.0)
+ oy.append(i)
+ for i in range(-10, 61):
+ ox.append(i)
+ oy.append(60.0)
+ for i in range(-10, 61):
+ ox.append(-10.0)
+ oy.append(i)
+ for i in range(-10, 40):
+ ox.append(20.0)
+ oy.append(i)
+ for i in range(0, 40):
+ ox.append(40.0)
+ oy.append(60.0 - i)
+
+ if show_animation: # pragma: no cover
+ plt.plot(ox, oy, ".k")
+ plt.plot(sx, sy, "og")
+ plt.plot(gx, gy, "xb")
+ plt.grid(True)
+ plt.axis("equal")
+
+ greedybestfirst = BestFirstSearchPlanner(ox, oy, grid_size, robot_radius)
+ rx, ry = greedybestfirst.planning(sx, sy, gx, gy)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.01)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py
new file mode 100644
index 0000000000..10ba98cd35
--- /dev/null
+++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py
@@ -0,0 +1,321 @@
+"""
+Grid based sweep planner
+
+author: Atsushi Sakai
+"""
+
+import math
+from enum import IntEnum
+import numpy as np
+import matplotlib.pyplot as plt
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
+from utils.angle import rot_mat_2d
+from Mapping.grid_map_lib.grid_map_lib import GridMap, FloatGrid
+
+do_animation = True
+
+
+class SweepSearcher:
+ class SweepDirection(IntEnum):
+ UP = 1
+ DOWN = -1
+
+ class MovingDirection(IntEnum):
+ RIGHT = 1
+ LEFT = -1
+
+ def __init__(self,
+ moving_direction, sweep_direction, x_inds_goal_y, goal_y):
+ self.moving_direction = moving_direction
+ self.sweep_direction = sweep_direction
+ self.turing_window = []
+ self.update_turning_window()
+ self.x_indexes_goal_y = x_inds_goal_y
+ self.goal_y = goal_y
+
+ def move_target_grid(self, c_x_index, c_y_index, grid_map):
+ n_x_index = self.moving_direction + c_x_index
+ n_y_index = c_y_index
+
+ # found safe grid
+ if not self.check_occupied(n_x_index, n_y_index, grid_map):
+ return n_x_index, n_y_index
+ else: # occupied
+ next_c_x_index, next_c_y_index = self.find_safe_turning_grid(
+ c_x_index, c_y_index, grid_map)
+ if (next_c_x_index is None) and (next_c_y_index is None):
+ # moving backward
+ next_c_x_index = -self.moving_direction + c_x_index
+ next_c_y_index = c_y_index
+ if self.check_occupied(next_c_x_index, next_c_y_index, grid_map, FloatGrid(1.0)):
+ # moved backward, but the grid is occupied by obstacle
+ return None, None
+ else:
+ # keep moving until end
+ while not self.check_occupied(next_c_x_index + self.moving_direction, next_c_y_index, grid_map):
+ next_c_x_index += self.moving_direction
+ self.swap_moving_direction()
+ return next_c_x_index, next_c_y_index
+
+ @staticmethod
+ def check_occupied(c_x_index, c_y_index, grid_map, occupied_val=FloatGrid(0.5)):
+ return grid_map.check_occupied_from_xy_index(c_x_index, c_y_index, occupied_val)
+
+ def find_safe_turning_grid(self, c_x_index, c_y_index, grid_map):
+
+ for (d_x_ind, d_y_ind) in self.turing_window:
+
+ next_x_ind = d_x_ind + c_x_index
+ next_y_ind = d_y_ind + c_y_index
+
+ # found safe grid
+ if not self.check_occupied(next_x_ind, next_y_ind, grid_map):
+ return next_x_ind, next_y_ind
+
+ return None, None
+
+ def is_search_done(self, grid_map):
+ for ix in self.x_indexes_goal_y:
+ if not self.check_occupied(ix, self.goal_y, grid_map):
+ return False
+
+ # all lower grid is occupied
+ return True
+
+ def update_turning_window(self):
+ # turning window definition
+ # robot can move grid based on it.
+ self.turing_window = [
+ (self.moving_direction, 0.0),
+ (self.moving_direction, self.sweep_direction),
+ (0, self.sweep_direction),
+ (-self.moving_direction, self.sweep_direction),
+ ]
+
+ def swap_moving_direction(self):
+ self.moving_direction *= -1
+ self.update_turning_window()
+
+ def search_start_grid(self, grid_map):
+ x_inds = []
+ y_ind = 0
+ if self.sweep_direction == self.SweepDirection.DOWN:
+ x_inds, y_ind = search_free_grid_index_at_edge_y(
+ grid_map, from_upper=True)
+ elif self.sweep_direction == self.SweepDirection.UP:
+ x_inds, y_ind = search_free_grid_index_at_edge_y(
+ grid_map, from_upper=False)
+
+ if self.moving_direction == self.MovingDirection.RIGHT:
+ return min(x_inds), y_ind
+ elif self.moving_direction == self.MovingDirection.LEFT:
+ return max(x_inds), y_ind
+
+ raise ValueError("self.moving direction is invalid ")
+
+
+def find_sweep_direction_and_start_position(ox, oy):
+ # find sweep_direction
+ max_dist = 0.0
+ vec = [0.0, 0.0]
+ sweep_start_pos = [0.0, 0.0]
+ for i in range(len(ox) - 1):
+ dx = ox[i + 1] - ox[i]
+ dy = oy[i + 1] - oy[i]
+ d = np.hypot(dx, dy)
+
+ if d > max_dist:
+ max_dist = d
+ vec = [dx, dy]
+ sweep_start_pos = [ox[i], oy[i]]
+
+ return vec, sweep_start_pos
+
+
+def convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_position):
+ tx = [ix - sweep_start_position[0] for ix in ox]
+ ty = [iy - sweep_start_position[1] for iy in oy]
+ th = math.atan2(sweep_vec[1], sweep_vec[0])
+ converted_xy = np.stack([tx, ty]).T @ rot_mat_2d(th)
+
+ return converted_xy[:, 0], converted_xy[:, 1]
+
+
+def convert_global_coordinate(x, y, sweep_vec, sweep_start_position):
+ th = math.atan2(sweep_vec[1], sweep_vec[0])
+ converted_xy = np.stack([x, y]).T @ rot_mat_2d(-th)
+ rx = [ix + sweep_start_position[0] for ix in converted_xy[:, 0]]
+ ry = [iy + sweep_start_position[1] for iy in converted_xy[:, 1]]
+ return rx, ry
+
+
+def search_free_grid_index_at_edge_y(grid_map, from_upper=False):
+ y_index = None
+ x_indexes = []
+
+ if from_upper:
+ x_range = range(grid_map.height)[::-1]
+ y_range = range(grid_map.width)[::-1]
+ else:
+ x_range = range(grid_map.height)
+ y_range = range(grid_map.width)
+
+ for iy in x_range:
+ for ix in y_range:
+ if not SweepSearcher.check_occupied(ix, iy, grid_map):
+ y_index = iy
+ x_indexes.append(ix)
+ if y_index:
+ break
+
+ return x_indexes, y_index
+
+
+def setup_grid_map(ox, oy, resolution, sweep_direction, offset_grid=10):
+ width = math.ceil((max(ox) - min(ox)) / resolution) + offset_grid
+ height = math.ceil((max(oy) - min(oy)) / resolution) + offset_grid
+ center_x = (np.max(ox) + np.min(ox)) / 2.0
+ center_y = (np.max(oy) + np.min(oy)) / 2.0
+
+ grid_map = GridMap(width, height, resolution, center_x, center_y)
+ grid_map.print_grid_map_info()
+ grid_map.set_value_from_polygon(ox, oy, FloatGrid(1.0), inside=False)
+ grid_map.expand_grid()
+
+ x_inds_goal_y = []
+ goal_y = 0
+ if sweep_direction == SweepSearcher.SweepDirection.UP:
+ x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(
+ grid_map, from_upper=True)
+ elif sweep_direction == SweepSearcher.SweepDirection.DOWN:
+ x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(
+ grid_map, from_upper=False)
+
+ return grid_map, x_inds_goal_y, goal_y
+
+
+def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False):
+ # search start grid
+ c_x_index, c_y_index = sweep_searcher.search_start_grid(grid_map)
+ if not grid_map.set_value_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5)):
+ print("Cannot find start grid")
+ return [], []
+
+ x, y = grid_map.calc_grid_central_xy_position_from_xy_index(c_x_index,
+ c_y_index)
+ px, py = [x], [y]
+
+ fig, ax = None, None
+ if grid_search_animation:
+ fig, ax = plt.subplots()
+ # for stopping simulation with the esc key.
+ fig.canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
+ while True:
+ c_x_index, c_y_index = sweep_searcher.move_target_grid(c_x_index,
+ c_y_index,
+ grid_map)
+
+ if sweep_searcher.is_search_done(grid_map) or (
+ c_x_index is None or c_y_index is None):
+ print("Done")
+ break
+
+ x, y = grid_map.calc_grid_central_xy_position_from_xy_index(
+ c_x_index, c_y_index)
+
+ px.append(x)
+ py.append(y)
+
+ grid_map.set_value_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5))
+
+ if grid_search_animation:
+ grid_map.plot_grid_map(ax=ax)
+ plt.pause(1.0)
+
+ return px, py
+
+
+def planning(ox, oy, resolution,
+ moving_direction=SweepSearcher.MovingDirection.RIGHT,
+ sweeping_direction=SweepSearcher.SweepDirection.UP,
+ ):
+ sweep_vec, sweep_start_position = find_sweep_direction_and_start_position(
+ ox, oy)
+
+ rox, roy = convert_grid_coordinate(ox, oy, sweep_vec,
+ sweep_start_position)
+
+ grid_map, x_inds_goal_y, goal_y = setup_grid_map(rox, roy, resolution,
+ sweeping_direction)
+
+ sweep_searcher = SweepSearcher(moving_direction, sweeping_direction,
+ x_inds_goal_y, goal_y)
+
+ px, py = sweep_path_search(sweep_searcher, grid_map)
+
+ rx, ry = convert_global_coordinate(px, py, sweep_vec,
+ sweep_start_position)
+
+ print("Path length:", len(rx))
+
+ return rx, ry
+
+
+def planning_animation(ox, oy, resolution): # pragma: no cover
+ px, py = planning(ox, oy, resolution)
+
+ # animation
+ if do_animation:
+ for ipx, ipy in zip(px, py):
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(ox, oy, "-xb")
+ plt.plot(px, py, "-r")
+ plt.plot(ipx, ipy, "or")
+ plt.axis("equal")
+ plt.grid(True)
+ plt.pause(0.1)
+
+ plt.cla()
+ plt.plot(ox, oy, "-xb")
+ plt.plot(px, py, "-r")
+ plt.axis("equal")
+ plt.grid(True)
+ plt.pause(0.1)
+ plt.close()
+
+
+def main(): # pragma: no cover
+ print("start!!")
+
+ ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0]
+ oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0]
+ resolution = 5.0
+ planning_animation(ox, oy, resolution)
+
+ ox = [0.0, 50.0, 50.0, 0.0, 0.0]
+ oy = [0.0, 0.0, 30.0, 30.0, 0.0]
+ resolution = 1.3
+ planning_animation(ox, oy, resolution)
+
+ ox = [0.0, 20.0, 50.0, 200.0, 130.0, 40.0, 0.0]
+ oy = [0.0, -80.0, 0.0, 30.0, 60.0, 80.0, 0.0]
+ resolution = 5.0
+ planning_animation(ox, oy, resolution)
+
+ if do_animation:
+ plt.show()
+ print("done!!")
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/HybridAStar/__init__.py b/PathPlanning/HybridAStar/__init__.py
new file mode 100644
index 0000000000..087dab646e
--- /dev/null
+++ b/PathPlanning/HybridAStar/__init__.py
@@ -0,0 +1,4 @@
+import os
+import sys
+
+sys.path.append(os.path.dirname(os.path.abspath(__file__)))
diff --git a/PathPlanning/HybridAStar/a_star.py b/PathPlanning/HybridAStar/a_star.py
deleted file mode 100644
index c1c82edd0d..0000000000
--- a/PathPlanning/HybridAStar/a_star.py
+++ /dev/null
@@ -1,231 +0,0 @@
-"""
-
-A* grid based planning
-
-author: Nikos Kanargias (nkana@tee.gr)
-
-See Wikipedia article (https://en.wikipedia.org/wiki/A*_search_algorithm)
-
-"""
-
-import math
-import heapq
-import matplotlib.pyplot as plt
-
-show_animation = False
-
-
-class Node:
-
- def __init__(self, x, y, cost, pind):
- self.x = x
- self.y = y
- self.cost = cost
- self.pind = pind
-
- def __str__(self):
- return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
-
-
-def calc_final_path(ngoal, closedset, reso):
- # generate final course
- rx, ry = [ngoal.x * reso], [ngoal.y * reso]
- pind = ngoal.pind
- while pind != -1:
- n = closedset[pind]
- rx.append(n.x * reso)
- ry.append(n.y * reso)
- pind = n.pind
-
- return rx, ry
-
-
-def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr):
- """
- gx: goal x position [m]
- gx: goal x position [m]
- ox: x position list of Obstacles [m]
- oy: y position list of Obstacles [m]
- reso: grid resolution [m]
- rr: robot radius[m]
- """
-
- nstart = Node(round(sx / reso), round(sy / reso), 0.0, -1)
- ngoal = Node(round(gx / reso), round(gy / reso), 0.0, -1)
- ox = [iox / reso for iox in ox]
- oy = [ioy / reso for ioy in oy]
-
- obmap, minx, miny, maxx, maxy, xw, yw = calc_obstacle_map(ox, oy, reso, rr)
-
- motion = get_motion_model()
-
- openset, closedset = dict(), dict()
- openset[calc_index(ngoal, xw, minx, miny)] = ngoal
- pq = []
- pq.append((0, calc_index(ngoal, xw, minx, miny)))
-
- while 1:
- if not pq:
- break
- cost, c_id = heapq.heappop(pq)
- if c_id in openset:
- current = openset[c_id]
- closedset[c_id] = current
- openset.pop(c_id)
- else:
- continue
-
- # show graph
- if show_animation: # pragma: no cover
- plt.plot(current.x * reso, current.y * reso, "xc")
- if len(closedset.keys()) % 10 == 0:
- plt.pause(0.001)
-
- # Remove the item from the open set
-
- # expand search grid based on motion model
- for i, _ in enumerate(motion):
- node = Node(current.x + motion[i][0],
- current.y + motion[i][1],
- current.cost + motion[i][2], c_id)
- n_id = calc_index(node, xw, minx, miny)
-
- if n_id in closedset:
- continue
-
- if not verify_node(node, obmap, minx, miny, maxx, maxy):
- continue
-
- if n_id not in openset:
- openset[n_id] = node # Discover a new node
- heapq.heappush(
- pq, (node.cost, calc_index(node, xw, minx, miny)))
- else:
- if openset[n_id].cost >= node.cost:
- # This path is the best until now. record it!
- openset[n_id] = node
- heapq.heappush(
- pq, (node.cost, calc_index(node, xw, minx, miny)))
-
- rx, ry = calc_final_path(closedset[calc_index(
- nstart, xw, minx, miny)], closedset, reso)
-
- return rx, ry, closedset
-
-
-def calc_heuristic(n1, n2):
- w = 1.0 # weight of heuristic
- d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2)
- return d
-
-
-def verify_node(node, obmap, minx, miny, maxx, maxy):
-
- if node.x < minx:
- return False
- elif node.y < miny:
- return False
- elif node.x >= maxx:
- return False
- elif node.y >= maxy:
- return False
-
- if obmap[node.x][node.y]:
- return False
-
- return True
-
-
-def calc_obstacle_map(ox, oy, reso, vr):
-
- minx = round(min(ox))
- miny = round(min(oy))
- maxx = round(max(ox))
- maxy = round(max(oy))
-
- xwidth = round(maxx - minx)
- ywidth = round(maxy - miny)
-
- # obstacle map generation
- obmap = [[False for i in range(ywidth)] for i in range(xwidth)]
- for ix in range(xwidth):
- x = ix + minx
- for iy in range(ywidth):
- y = iy + miny
- # print(x, y)
- for iox, ioy in zip(ox, oy):
- d = math.sqrt((iox - x)**2 + (ioy - y)**2)
- if d <= vr / reso:
- obmap[ix][iy] = True
- break
-
- return obmap, minx, miny, maxx, maxy, xwidth, ywidth
-
-
-def calc_index(node, xwidth, xmin, ymin):
- return (node.y - ymin) * xwidth + (node.x - xmin)
-
-
-def get_motion_model():
- # dx, dy, cost
- motion = [[1, 0, 1],
- [0, 1, 1],
- [-1, 0, 1],
- [0, -1, 1],
- [-1, -1, math.sqrt(2)],
- [-1, 1, math.sqrt(2)],
- [1, -1, math.sqrt(2)],
- [1, 1, math.sqrt(2)]]
-
- return motion
-
-
-def main():
- print(__file__ + " start!!")
-
- # start and goal position
- sx = 10.0 # [m]
- sy = 10.0 # [m]
- gx = 50.0 # [m]
- gy = 50.0 # [m]
- grid_size = 2.0 # [m]
- robot_size = 1.0 # [m]
-
- ox, oy = [], []
-
- for i in range(60):
- ox.append(i)
- oy.append(0.0)
- for i in range(60):
- ox.append(60.0)
- oy.append(i)
- for i in range(61):
- ox.append(i)
- oy.append(60.0)
- for i in range(61):
- ox.append(0.0)
- oy.append(i)
- for i in range(40):
- ox.append(20.0)
- oy.append(i)
- for i in range(40):
- ox.append(40.0)
- oy.append(60.0 - i)
-
- if show_animation: # pragma: no cover
- plt.plot(ox, oy, ".k")
- plt.plot(sx, sy, "xr")
- plt.plot(gx, gy, "xb")
- plt.grid(True)
- plt.axis("equal")
-
- rx, ry, _ = dp_planning(sx, sy, gx, gy, ox, oy, grid_size, robot_size)
-
- if show_animation: # pragma: no cover
- plt.plot(rx, ry, "-r")
- plt.show()
-
-
-if __name__ == '__main__':
- show_animation = True
- main()
\ No newline at end of file
diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py
index 13e50b2995..959db74078 100644
--- a/PathPlanning/HybridAStar/car.py
+++ b/PathPlanning/HybridAStar/car.py
@@ -6,35 +6,43 @@
"""
+import sys
+import pathlib
+root_dir = pathlib.Path(__file__).parent.parent.parent
+sys.path.append(str(root_dir))
+
+from math import cos, sin, tan, pi
import matplotlib.pyplot as plt
-from math import sqrt, cos, sin, tan, pi
+import numpy as np
+
+from utils.angle import rot_mat_2d
-WB = 3. # rear to front wheel
-W = 2. # width of car
+WB = 3.0 # rear to front wheel
+W = 2.0 # width of car
LF = 3.3 # distance from rear to vehicle front end
LB = 1.0 # distance from rear to vehicle back end
MAX_STEER = 0.6 # [rad] maximum steering angle
-WBUBBLE_DIST = (LF - LB) / 2.0
-WBUBBLE_R = sqrt(((LF + LB) / 2.0)**2 + 1)
+BUBBLE_DIST = (LF - LB) / 2.0 # distance from rear to center of vehicle.
+BUBBLE_R = np.hypot((LF + LB) / 2.0, W / 2.0) # bubble radius
-# vehicle rectangle verticles
+# vehicle rectangle vertices
VRX = [LF, LF, -LB, -LB, LF]
VRY = [W / 2, -W / 2, -W / 2, W / 2, W / 2]
-def check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree):
- for x, y, yaw in zip(xlist, ylist, yawlist):
- cx = x + WBUBBLE_DIST * cos(yaw)
- cy = y + WBUBBLE_DIST * sin(yaw)
+def check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree):
+ for i_x, i_y, i_yaw in zip(x_list, y_list, yaw_list):
+ cx = i_x + BUBBLE_DIST * cos(i_yaw)
+ cy = i_y + BUBBLE_DIST * sin(i_yaw)
- ids = kdtree.search_in_distance([cx, cy], WBUBBLE_R)
+ ids = kd_tree.query_ball_point([cx, cy], BUBBLE_R)
if not ids:
continue
- if not rectangle_check(x, y, yaw,
+ if not rectangle_check(i_x, i_y, i_yaw,
[ox[i] for i in ids], [oy[i] for i in ids]):
return False # collision
@@ -43,40 +51,38 @@ def check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree):
def rectangle_check(x, y, yaw, ox, oy):
# transform obstacles to base link frame
- c, s = cos(-yaw), sin(-yaw)
+ rot = rot_mat_2d(yaw)
for iox, ioy in zip(ox, oy):
tx = iox - x
ty = ioy - y
- rx = c * tx - s * ty
- ry = s * tx + c * ty
+ converted_xy = np.stack([tx, ty]).T @ rot
+ rx, ry = converted_xy[0], converted_xy[1]
if not (rx > LF or rx < -LB or ry > W / 2.0 or ry < -W / 2.0):
- return False # no collision
+ return False # collision
- return True # collision
+ return True # no collision
def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
"""Plot arrow."""
if not isinstance(x, float):
- for (ix, iy, iyaw) in zip(x, y, yaw):
- plot_arrow(ix, iy, iyaw)
+ for (i_x, i_y, i_yaw) in zip(x, y, yaw):
+ plot_arrow(i_x, i_y, i_yaw)
else:
plt.arrow(x, y, length * cos(yaw), length * sin(yaw),
fc=fc, ec=ec, head_width=width, head_length=width, alpha=0.4)
- # plt.plot(x, y)
def plot_car(x, y, yaw):
car_color = '-k'
c, s = cos(yaw), sin(yaw)
-
+ rot = rot_mat_2d(-yaw)
car_outline_x, car_outline_y = [], []
for rx, ry in zip(VRX, VRY):
- tx = c * rx - s * ry + x
- ty = s * rx + c * ry + y
- car_outline_x.append(tx)
- car_outline_y.append(ty)
+ converted_xy = np.stack([rx, ry]).T @ rot
+ car_outline_x.append(converted_xy[0]+x)
+ car_outline_y.append(converted_xy[1]+y)
arrow_x, arrow_y, arrow_yaw = c * 1.5 + x, s * 1.5 + y, yaw
plot_arrow(arrow_x, arrow_y, arrow_yaw)
@@ -91,13 +97,17 @@ def pi_2_pi(angle):
def move(x, y, yaw, distance, steer, L=WB):
x += distance * cos(yaw)
y += distance * sin(yaw)
- yaw += pi_2_pi(distance * tan(steer) / L) # distance/2
+ yaw = pi_2_pi(yaw + distance * tan(steer) / L) # distance/2
return x, y, yaw
-if __name__ == '__main__':
+def main():
x, y, yaw = 0., 0., 1.
plt.axis('equal')
plot_car(x, y, yaw)
- plt.show()
\ No newline at end of file
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/HybridAStar/dynamic_programming_heuristic.py b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py
new file mode 100644
index 0000000000..09bcd556a6
--- /dev/null
+++ b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py
@@ -0,0 +1,176 @@
+"""
+
+A* grid based planning
+
+author: Nikos Kanargias (nkana@tee.gr)
+
+See Wikipedia article (https://en.wikipedia.org/wiki/A*_search_algorithm)
+
+"""
+
+import heapq
+import math
+
+import matplotlib.pyplot as plt
+
+show_animation = False
+
+
+class Node:
+
+ def __init__(self, x, y, cost, parent_index):
+ self.x = x
+ self.y = y
+ self.cost = cost
+ self.parent_index = parent_index
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent_index)
+
+
+def calc_final_path(goal_node, closed_node_set, resolution):
+ # generate final course
+ rx, ry = [goal_node.x * resolution], [goal_node.y * resolution]
+ parent_index = goal_node.parent_index
+ while parent_index != -1:
+ n = closed_node_set[parent_index]
+ rx.append(n.x * resolution)
+ ry.append(n.y * resolution)
+ parent_index = n.parent_index
+
+ return rx, ry
+
+
+def calc_distance_heuristic(gx, gy, ox, oy, resolution, rr):
+ """
+ gx: goal x position [m]
+ gx: goal x position [m]
+ ox: x position list of Obstacles [m]
+ oy: y position list of Obstacles [m]
+ resolution: grid resolution [m]
+ rr: robot radius[m]
+ """
+
+ goal_node = Node(round(gx / resolution), round(gy / resolution), 0.0, -1)
+ ox = [iox / resolution for iox in ox]
+ oy = [ioy / resolution for ioy in oy]
+
+ obstacle_map, min_x, min_y, max_x, max_y, x_w, y_w = calc_obstacle_map(
+ ox, oy, resolution, rr)
+
+ motion = get_motion_model()
+
+ open_set, closed_set = dict(), dict()
+ open_set[calc_index(goal_node, x_w, min_x, min_y)] = goal_node
+ priority_queue = [(0, calc_index(goal_node, x_w, min_x, min_y))]
+
+ while True:
+ if not priority_queue:
+ break
+ cost, c_id = heapq.heappop(priority_queue)
+ if c_id in open_set:
+ current = open_set[c_id]
+ closed_set[c_id] = current
+ open_set.pop(c_id)
+ else:
+ continue
+
+ # show graph
+ if show_animation: # pragma: no cover
+ plt.plot(current.x * resolution, current.y * resolution, "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if len(closed_set.keys()) % 10 == 0:
+ plt.pause(0.001)
+
+ # Remove the item from the open set
+
+ # expand search grid based on motion model
+ for i, _ in enumerate(motion):
+ node = Node(current.x + motion[i][0],
+ current.y + motion[i][1],
+ current.cost + motion[i][2], c_id)
+ n_id = calc_index(node, x_w, min_x, min_y)
+
+ if n_id in closed_set:
+ continue
+
+ if not verify_node(node, obstacle_map, min_x, min_y, max_x, max_y):
+ continue
+
+ if n_id not in open_set:
+ open_set[n_id] = node # Discover a new node
+ heapq.heappush(
+ priority_queue,
+ (node.cost, calc_index(node, x_w, min_x, min_y)))
+ else:
+ if open_set[n_id].cost >= node.cost:
+ # This path is the best until now. record it!
+ open_set[n_id] = node
+ heapq.heappush(
+ priority_queue,
+ (node.cost, calc_index(node, x_w, min_x, min_y)))
+
+ return closed_set
+
+
+def verify_node(node, obstacle_map, min_x, min_y, max_x, max_y):
+ if node.x < min_x:
+ return False
+ elif node.y < min_y:
+ return False
+ elif node.x >= max_x:
+ return False
+ elif node.y >= max_y:
+ return False
+
+ if obstacle_map[node.x][node.y]:
+ return False
+
+ return True
+
+
+def calc_obstacle_map(ox, oy, resolution, vr):
+ min_x = round(min(ox))
+ min_y = round(min(oy))
+ max_x = round(max(ox))
+ max_y = round(max(oy))
+
+ x_width = round(max_x - min_x)
+ y_width = round(max_y - min_y)
+
+ # obstacle map generation
+ obstacle_map = [[False for _ in range(y_width)] for _ in range(x_width)]
+ for ix in range(x_width):
+ x = ix + min_x
+ for iy in range(y_width):
+ y = iy + min_y
+ # print(x, y)
+ for iox, ioy in zip(ox, oy):
+ d = math.hypot(iox - x, ioy - y)
+ if d <= vr / resolution:
+ obstacle_map[ix][iy] = True
+ break
+
+ return obstacle_map, min_x, min_y, max_x, max_y, x_width, y_width
+
+
+def calc_index(node, x_width, x_min, y_min):
+ return (node.y - y_min) * x_width + (node.x - x_min)
+
+
+def get_motion_model():
+ # dx, dy, cost
+ motion = [[1, 0, 1],
+ [0, 1, 1],
+ [-1, 0, 1],
+ [0, -1, 1],
+ [-1, -1, math.sqrt(2)],
+ [-1, 1, math.sqrt(2)],
+ [1, -1, math.sqrt(2)],
+ [1, 1, math.sqrt(2)]]
+
+ return motion
diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py
index e82003ed25..0fa04189c6 100644
--- a/PathPlanning/HybridAStar/hybrid_a_star.py
+++ b/PathPlanning/HybridAStar/hybrid_a_star.py
@@ -7,26 +7,22 @@
"""
import heapq
-import scipy.spatial
-import numpy as np
import math
import matplotlib.pyplot as plt
+import numpy as np
+from scipy.spatial import cKDTree
import sys
-sys.path.append("../ReedsSheppPath/")
-try:
- from a_star import dp_planning # , calc_obstacle_map
- import reeds_shepp_path_planning as rs
- from car import move, check_car_collision, MAX_STEER, WB, plot_car
-except:
- raise
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+from dynamic_programming_heuristic import calc_distance_heuristic
+from ReedsSheppPath import reeds_shepp_path_planning as rs
+from car import move, check_car_collision, MAX_STEER, WB, plot_car, BUBBLE_R
XY_GRID_RESOLUTION = 2.0 # [m]
YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad]
-MOTION_RESOLUTION = 0.1 # [m] path interporate resolution
-N_STEER = 20.0 # number of steer command
-H_COST = 1.0
-VR = 1.0 # robot radius
+MOTION_RESOLUTION = 0.1 # [m] path interpolate resolution
+N_STEER = 20 # number of steer command
SB_COST = 100.0 # switch back penalty cost
BACK_COST = 5.0 # backward penalty cost
@@ -39,73 +35,35 @@
class Node:
- def __init__(self, xind, yind, yawind, direction,
- xlist, ylist, yawlist, directions,
- steer=0.0, pind=None, cost=None):
- self.xind = xind
- self.yind = yind
- self.yawind = yawind
+ def __init__(self, x_ind, y_ind, yaw_ind, direction,
+ x_list, y_list, yaw_list, directions,
+ steer=0.0, parent_index=None, cost=None):
+ self.x_index = x_ind
+ self.y_index = y_ind
+ self.yaw_index = yaw_ind
self.direction = direction
- self.xlist = xlist
- self.ylist = ylist
- self.yawlist = yawlist
+ self.x_list = x_list
+ self.y_list = y_list
+ self.yaw_list = yaw_list
self.directions = directions
self.steer = steer
- self.pind = pind
+ self.parent_index = parent_index
self.cost = cost
class Path:
- def __init__(self, xlist, ylist, yawlist, directionlist, cost):
- self.xlist = xlist
- self.ylist = ylist
- self.yawlist = yawlist
- self.directionlist = directionlist
+ def __init__(self, x_list, y_list, yaw_list, direction_list, cost):
+ self.x_list = x_list
+ self.y_list = y_list
+ self.yaw_list = yaw_list
+ self.direction_list = direction_list
self.cost = cost
-class KDTree:
- """
- Nearest neighbor search class with KDTree
- """
-
- def __init__(self, data):
- # store kd-tree
- self.tree = scipy.spatial.cKDTree(data)
-
- def search(self, inp, k=1):
- """
- Search NN
- inp: input data, single frame or multi frame
- """
-
- if len(inp.shape) >= 2: # multi input
- index = []
- dist = []
-
- for i in inp.T:
- idist, iindex = self.tree.query(i, k=k)
- index.append(iindex)
- dist.append(idist)
-
- return index, dist
-
- dist, index = self.tree.query(inp, k=k)
- return index, dist
-
- def search_in_distance(self, inp, r):
- """
- find points with in a distance r
- """
-
- index = self.tree.query_ball_point(inp, r)
- return index
-
-
class Config:
- def __init__(self, ox, oy, xyreso, yawreso):
+ def __init__(self, ox, oy, xy_resolution, yaw_resolution):
min_x_m = min(ox)
min_y_m = min(oy)
max_x_m = max(ox)
@@ -116,93 +74,94 @@ def __init__(self, ox, oy, xyreso, yawreso):
ox.append(max_x_m)
oy.append(max_y_m)
- self.minx = round(min_x_m / xyreso)
- self.miny = round(min_y_m / xyreso)
- self.maxx = round(max_x_m / xyreso)
- self.maxy = round(max_y_m / xyreso)
+ self.min_x = round(min_x_m / xy_resolution)
+ self.min_y = round(min_y_m / xy_resolution)
+ self.max_x = round(max_x_m / xy_resolution)
+ self.max_y = round(max_y_m / xy_resolution)
- self.xw = round(self.maxx - self.minx)
- self.yw = round(self.maxy - self.miny)
+ self.x_w = round(self.max_x - self.min_x)
+ self.y_w = round(self.max_y - self.min_y)
- self.minyaw = round(- math.pi / yawreso) - 1
- self.maxyaw = round(math.pi / yawreso)
- self.yaww = round(self.maxyaw - self.minyaw)
+ self.min_yaw = round(- math.pi / yaw_resolution) - 1
+ self.max_yaw = round(math.pi / yaw_resolution)
+ self.yaw_w = round(self.max_yaw - self.min_yaw)
def calc_motion_inputs():
-
- for steer in np.concatenate((np.linspace(-MAX_STEER, MAX_STEER, N_STEER),[0.0])):
+ for steer in np.concatenate((np.linspace(-MAX_STEER, MAX_STEER,
+ N_STEER), [0.0])):
for d in [1, -1]:
yield [steer, d]
-def get_neighbors(current, config, ox, oy, kdtree):
-
+def get_neighbors(current, config, ox, oy, kd_tree):
for steer, d in calc_motion_inputs():
- node = calc_next_node(current, steer, d, config, ox, oy, kdtree)
+ node = calc_next_node(current, steer, d, config, ox, oy, kd_tree)
if node and verify_index(node, config):
yield node
-def calc_next_node(current, steer, direction, config, ox, oy, kdtree):
-
- x, y, yaw = current.xlist[-1], current.ylist[-1], current.yawlist[-1]
+def calc_next_node(current, steer, direction, config, ox, oy, kd_tree):
+ x, y, yaw = current.x_list[-1], current.y_list[-1], current.yaw_list[-1]
arc_l = XY_GRID_RESOLUTION * 1.5
- xlist, ylist, yawlist = [], [], []
- for dist in np.arange(0, arc_l, MOTION_RESOLUTION):
+ x_list, y_list, yaw_list, direction_list = [], [], [], []
+ for _ in np.arange(0, arc_l, MOTION_RESOLUTION):
x, y, yaw = move(x, y, yaw, MOTION_RESOLUTION * direction, steer)
- xlist.append(x)
- ylist.append(y)
- yawlist.append(yaw)
+ x_list.append(x)
+ y_list.append(y)
+ yaw_list.append(yaw)
+ direction_list.append(direction == 1)
- if not check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree):
+ if not check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree):
return None
d = direction == 1
- xind = round(x / XY_GRID_RESOLUTION)
- yind = round(y / XY_GRID_RESOLUTION)
- yawind = round(yaw / YAW_GRID_RESOLUTION)
+ x_ind = round(x / XY_GRID_RESOLUTION)
+ y_ind = round(y / XY_GRID_RESOLUTION)
+ yaw_ind = round(yaw / YAW_GRID_RESOLUTION)
- addedcost = 0.0
+ added_cost = 0.0
if d != current.direction:
- addedcost += SB_COST
+ added_cost += SB_COST
# steer penalty
- addedcost += STEER_COST * abs(steer)
+ added_cost += STEER_COST * abs(steer)
# steer change penalty
- addedcost += STEER_CHANGE_COST * abs(current.steer - steer)
+ added_cost += STEER_CHANGE_COST * abs(current.steer - steer)
- cost = current.cost + addedcost + arc_l
+ cost = current.cost + added_cost + arc_l
- node = Node(xind, yind, yawind, d, xlist,
- ylist, yawlist, [d],
- pind=calc_index(current, config),
+ node = Node(x_ind, y_ind, yaw_ind, d, x_list,
+ y_list, yaw_list, direction_list,
+ parent_index=calc_index(current, config),
cost=cost, steer=steer)
return node
def is_same_grid(n1, n2):
- if n1.xind == n2.xind and n1.yind == n2.yind and n1.yawind == n2.yawind:
+ if n1.x_index == n2.x_index \
+ and n1.y_index == n2.y_index \
+ and n1.yaw_index == n2.yaw_index:
return True
return False
-def analytic_expantion(current, goal, c, ox, oy, kdtree):
-
- sx = current.xlist[-1]
- sy = current.ylist[-1]
- syaw = current.yawlist[-1]
+def analytic_expansion(current, goal, ox, oy, kd_tree):
+ start_x = current.x_list[-1]
+ start_y = current.y_list[-1]
+ start_yaw = current.yaw_list[-1]
- gx = goal.xlist[-1]
- gy = goal.ylist[-1]
- gyaw = goal.yawlist[-1]
+ goal_x = goal.x_list[-1]
+ goal_y = goal.y_list[-1]
+ goal_yaw = goal.yaw_list[-1]
max_curvature = math.tan(MAX_STEER) / WB
- paths = rs.calc_paths(sx, sy, syaw, gx, gy, gyaw,
+ paths = rs.calc_paths(start_x, start_y, start_yaw,
+ goal_x, goal_y, goal_yaw,
max_curvature, step_size=MOTION_RESOLUTION)
if not paths:
@@ -211,7 +170,7 @@ def analytic_expantion(current, goal, c, ox, oy, kdtree):
best_path, best = None, None
for path in paths:
- if check_car_collision(path.x, path.y, path.yaw, ox, oy, kdtree):
+ if check_car_collision(path.x, path.y, path.yaw, ox, oy, kd_tree):
cost = calc_rs_path_cost(path)
if not best or best > cost:
best = cost
@@ -220,103 +179,110 @@ def analytic_expantion(current, goal, c, ox, oy, kdtree):
return best_path
-def update_node_with_analystic_expantion(current, goal,
- c, ox, oy, kdtree):
- apath = analytic_expantion(current, goal, c, ox, oy, kdtree)
+def update_node_with_analytic_expansion(current, goal,
+ c, ox, oy, kd_tree):
+ path = analytic_expansion(current, goal, ox, oy, kd_tree)
- if apath:
- plt.plot(apath.x, apath.y)
- fx = apath.x[1:]
- fy = apath.y[1:]
- fyaw = apath.yaw[1:]
+ if path:
+ if show_animation:
+ plt.plot(path.x, path.y)
+ f_x = path.x[1:]
+ f_y = path.y[1:]
+ f_yaw = path.yaw[1:]
- fcost = current.cost + calc_rs_path_cost(apath)
- fpind = calc_index(current, c)
+ f_cost = current.cost + calc_rs_path_cost(path)
+ f_parent_index = calc_index(current, c)
fd = []
- for d in apath.directions[1:]:
+ for d in path.directions[1:]:
fd.append(d >= 0)
- fsteer = 0.0
- fpath = Node(current.xind, current.yind, current.yawind,
- current.direction, fx, fy, fyaw, fd,
- cost=fcost, pind=fpind, steer=fsteer)
- return True, fpath
+ f_steer = 0.0
+ f_path = Node(current.x_index, current.y_index, current.yaw_index,
+ current.direction, f_x, f_y, f_yaw, fd,
+ cost=f_cost, parent_index=f_parent_index, steer=f_steer)
+ return True, f_path
return False, None
-def calc_rs_path_cost(rspath):
-
+def calc_rs_path_cost(reed_shepp_path):
cost = 0.0
- for l in rspath.lengths:
- if l >= 0: # forward
- cost += l
+ for length in reed_shepp_path.lengths:
+ if length >= 0: # forward
+ cost += length
else: # back
- cost += abs(l) * BACK_COST
+ cost += abs(length) * BACK_COST
- # swich back penalty
- for i in range(len(rspath.lengths) - 1):
- if rspath.lengths[i] * rspath.lengths[i + 1] < 0.0: # switch back
+ # switch back penalty
+ for i in range(len(reed_shepp_path.lengths) - 1):
+ # switch back
+ if reed_shepp_path.lengths[i] * reed_shepp_path.lengths[i + 1] < 0.0:
cost += SB_COST
- # steer penalyty
- for ctype in rspath.ctypes:
- if ctype != "S": # curve
+ # steer penalty
+ for course_type in reed_shepp_path.ctypes:
+ if course_type != "S": # curve
cost += STEER_COST * abs(MAX_STEER)
# ==steer change penalty
# calc steer profile
- nctypes = len(rspath.ctypes)
- ulist = [0.0] * nctypes
- for i in range(nctypes):
- if rspath.ctypes[i] == "R":
- ulist[i] = - MAX_STEER
- elif rspath.ctypes[i] == "L":
- ulist[i] = MAX_STEER
+ n_ctypes = len(reed_shepp_path.ctypes)
+ u_list = [0.0] * n_ctypes
+ for i in range(n_ctypes):
+ if reed_shepp_path.ctypes[i] == "R":
+ u_list[i] = - MAX_STEER
+ elif reed_shepp_path.ctypes[i] == "L":
+ u_list[i] = MAX_STEER
- for i in range(len(rspath.ctypes) - 1):
- cost += STEER_CHANGE_COST * abs(ulist[i + 1] - ulist[i])
+ for i in range(len(reed_shepp_path.ctypes) - 1):
+ cost += STEER_CHANGE_COST * abs(u_list[i + 1] - u_list[i])
return cost
-def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso):
+def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution):
"""
- start
- goal
+ start: start node
+ goal: goal node
ox: x position list of Obstacles [m]
oy: y position list of Obstacles [m]
- xyreso: grid resolution [m]
- yawreso: yaw angle resolution [rad]
+ xy_resolution: grid resolution [m]
+ yaw_resolution: yaw angle resolution [rad]
"""
start[2], goal[2] = rs.pi_2_pi(start[2]), rs.pi_2_pi(goal[2])
tox, toy = ox[:], oy[:]
- obkdtree = KDTree(np.vstack((tox, toy)).T)
+ obstacle_kd_tree = cKDTree(np.vstack((tox, toy)).T)
- config = Config(tox, toy, xyreso, yawreso)
+ config = Config(tox, toy, xy_resolution, yaw_resolution)
- nstart = Node(round(start[0] / xyreso), round(start[1] / xyreso), round(start[2] / yawreso),
- True, [start[0]], [start[1]], [start[2]], [True], cost=0)
- ngoal = Node(round(goal[0] / xyreso), round(goal[1] / xyreso), round(goal[2] / yawreso),
- True, [goal[0]], [goal[1]], [goal[2]], [True])
+ start_node = Node(round(start[0] / xy_resolution),
+ round(start[1] / xy_resolution),
+ round(start[2] / yaw_resolution), True,
+ [start[0]], [start[1]], [start[2]], [True], cost=0)
+ goal_node = Node(round(goal[0] / xy_resolution),
+ round(goal[1] / xy_resolution),
+ round(goal[2] / yaw_resolution), True,
+ [goal[0]], [goal[1]], [goal[2]], [True])
openList, closedList = {}, {}
- _, _, h_dp = dp_planning(nstart.xlist[-1], nstart.ylist[-1],
- ngoal.xlist[-1], ngoal.ylist[-1], ox, oy, xyreso, VR)
+ h_dp = calc_distance_heuristic(
+ goal_node.x_list[-1], goal_node.y_list[-1],
+ ox, oy, xy_resolution, BUBBLE_R)
pq = []
- openList[calc_index(nstart, config)] = nstart
- heapq.heappush(pq, (calc_cost(nstart, h_dp, ngoal, config),
- calc_index(nstart, config)))
+ openList[calc_index(start_node, config)] = start_node
+ heapq.heappush(pq, (calc_cost(start_node, h_dp, config),
+ calc_index(start_node, config)))
+ final_path = None
while True:
if not openList:
print("Error: Cannot find path, No open set")
- return [], [], []
+ return Path([], [], [], [], 0)
cost, c_id = heapq.heappop(pq)
if c_id in openList:
@@ -326,79 +292,85 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso):
continue
if show_animation: # pragma: no cover
- plt.plot(current.xlist[-1], current.ylist[-1], "xc")
+ plt.plot(current.x_list[-1], current.y_list[-1], "xc")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
if len(closedList.keys()) % 10 == 0:
plt.pause(0.001)
- isupdated, fpath = update_node_with_analystic_expantion(
- current, ngoal, config, ox, oy, obkdtree)
+ is_updated, final_path = update_node_with_analytic_expansion(
+ current, goal_node, config, ox, oy, obstacle_kd_tree)
- if isupdated:
+ if is_updated:
+ print("path found")
break
- for neighbor in get_neighbors(current, config, ox, oy, obkdtree):
+ for neighbor in get_neighbors(current, config, ox, oy,
+ obstacle_kd_tree):
neighbor_index = calc_index(neighbor, config)
if neighbor_index in closedList:
continue
- if neighbor not in openList \
+ if neighbor_index not in openList \
or openList[neighbor_index].cost > neighbor.cost:
heapq.heappush(
- pq, (calc_cost(neighbor, h_dp, ngoal, config),
+ pq, (calc_cost(neighbor, h_dp, config),
neighbor_index))
openList[neighbor_index] = neighbor
- path = get_final_path(closedList, fpath, nstart, config)
+ path = get_final_path(closedList, final_path)
return path
-def calc_cost(n, h_dp, goal, c):
- ind = (n.yind - c.miny) * c.xw + (n.xind - c.minx)
+def calc_cost(n, h_dp, c):
+ ind = (n.y_index - c.min_y) * c.x_w + (n.x_index - c.min_x)
if ind not in h_dp:
return n.cost + 999999999 # collision cost
return n.cost + H_COST * h_dp[ind].cost
-def get_final_path(closed, ngoal, nstart, config):
- rx, ry, ryaw = list(reversed(ngoal.xlist)), list(
- reversed(ngoal.ylist)), list(reversed(ngoal.yawlist))
- direction = list(reversed(ngoal.directions))
- nid = ngoal.pind
- finalcost = ngoal.cost
+def get_final_path(closed, goal_node):
+ reversed_x, reversed_y, reversed_yaw = \
+ list(reversed(goal_node.x_list)), list(reversed(goal_node.y_list)), \
+ list(reversed(goal_node.yaw_list))
+ direction = list(reversed(goal_node.directions))
+ nid = goal_node.parent_index
+ final_cost = goal_node.cost
while nid:
n = closed[nid]
- rx.extend(list(reversed(n.xlist)))
- ry.extend(list(reversed(n.ylist)))
- ryaw.extend(list(reversed(n.yawlist)))
+ reversed_x.extend(list(reversed(n.x_list)))
+ reversed_y.extend(list(reversed(n.y_list)))
+ reversed_yaw.extend(list(reversed(n.yaw_list)))
direction.extend(list(reversed(n.directions)))
- nid = n.pind
+ nid = n.parent_index
- rx = list(reversed(rx))
- ry = list(reversed(ry))
- ryaw = list(reversed(ryaw))
+ reversed_x = list(reversed(reversed_x))
+ reversed_y = list(reversed(reversed_y))
+ reversed_yaw = list(reversed(reversed_yaw))
direction = list(reversed(direction))
# adjust first direction
direction[0] = direction[1]
- path = Path(rx, ry, ryaw, direction, finalcost)
+ path = Path(reversed_x, reversed_y, reversed_yaw, direction, final_cost)
return path
def verify_index(node, c):
- xind, yind = node.xind, node.yind
- if xind >= c.minx and xind <= c.maxx and yind >= c.miny \
- and yind <= c.maxy:
+ x_ind, y_ind = node.x_index, node.y_index
+ if c.min_x <= x_ind <= c.max_x and c.min_y <= y_ind <= c.max_y:
return True
return False
def calc_index(node, c):
- ind = (node.yawind - c.minyaw) * c.xw * c.yw + \
- (node.yind - c.miny) * c.xw + (node.xind - c.minx)
+ ind = (node.yaw_index - c.min_yaw) * c.x_w * c.y_w + \
+ (node.y_index - c.min_y) * c.x_w + (node.x_index - c.min_x)
if ind <= 0:
print("Error(calc_index):", ind)
@@ -434,28 +406,33 @@ def main():
start = [10.0, 10.0, np.deg2rad(90.0)]
goal = [50.0, 50.0, np.deg2rad(-90.0)]
- plt.plot(ox, oy, ".k")
- rs.plot_arrow(start[0], start[1], start[2], fc='g')
- rs.plot_arrow(goal[0], goal[1], goal[2])
+ print("start : ", start)
+ print("goal : ", goal)
+
+ if show_animation:
+ plt.plot(ox, oy, ".k")
+ rs.plot_arrow(start[0], start[1], start[2], fc='g')
+ rs.plot_arrow(goal[0], goal[1], goal[2])
- plt.grid(True)
- plt.axis("equal")
+ plt.grid(True)
+ plt.axis("equal")
path = hybrid_a_star_planning(
start, goal, ox, oy, XY_GRID_RESOLUTION, YAW_GRID_RESOLUTION)
- x = path.xlist
- y = path.ylist
- yaw = path.yawlist
-
- for ix, iy, iyaw in zip(x, y, yaw):
- plt.cla()
- plt.plot(ox, oy, ".k")
- plt.plot(x, y, "-r", label="Hybrid A* path")
- plt.grid(True)
- plt.axis("equal")
- plot_car(ix, iy, iyaw)
- plt.pause(0.0001)
+ x = path.x_list
+ y = path.y_list
+ yaw = path.yaw_list
+
+ if show_animation:
+ for i_x, i_y, i_yaw in zip(x, y, yaw):
+ plt.cla()
+ plt.plot(ox, oy, ".k")
+ plt.plot(x, y, "-r", label="Hybrid A* path")
+ plt.grid(True)
+ plt.axis("equal")
+ plot_car(i_x, i_y, i_yaw)
+ plt.pause(0.0001)
print(__file__ + " done!!")
diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py
index 2a999fd0c5..0483949c99 100644
--- a/PathPlanning/InformedRRTStar/informed_rrt_star.py
+++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py
@@ -4,151 +4,159 @@
author: Karan Chawla
Atsushi Sakai(@Atsushi_twi)
-Reference: Informed RRT*: Optimal Sampling-based Path Planning Focused via
-Direct Sampling of an Admissible Ellipsoidal Heuristichttps://arxiv.org/pdf/1404.2334.pdf
+Reference: Informed RRT*: Optimal Sampling-based Path planning Focused via
+Direct Sampling of an Admissible Ellipsoidal Heuristic
+https://arxiv.org/pdf/1404.2334
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
-import random
-import numpy as np
-import math
import copy
+import math
+import random
+
import matplotlib.pyplot as plt
+import numpy as np
+
+from utils.angle import rot_mat_2d
show_animation = True
-class InformedRRTStar():
+class InformedRRTStar:
- def __init__(self, start, goal,
- obstacleList, randArea,
- expandDis=0.5, goalSampleRate=10, maxIter=200):
+ def __init__(self, start, goal, obstacle_list, rand_area, expand_dis=0.5,
+ goal_sample_rate=10, max_iter=200):
self.start = Node(start[0], start[1])
self.goal = Node(goal[0], goal[1])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.expandDis = expandDis
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def InformedRRTStarSearch(self, animation=True):
-
- self.nodeList = [self.start]
- # max length we expect to find in our 'informed' sample space, starts as infinite
- cBest = float('inf')
- pathLen = float('inf')
- solutionSet = set()
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.expand_dis = expand_dis
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+ self.node_list = None
+
+ def informed_rrt_star_search(self, animation=True):
+
+ self.node_list = [self.start]
+ # max length we expect to find in our 'informed' sample space,
+ # starts as infinite
+ c_best = float('inf')
+ solution_set = set()
path = None
# Computing the sampling space
- cMin = math.sqrt(pow(self.start.x - self.goal.x, 2)
- + pow(self.start.y - self.goal.y, 2))
- xCenter = np.array([[(self.start.x + self.goal.x) / 2.0],
- [(self.start.y + self.goal.y) / 2.0], [0]])
- a1 = np.array([[(self.goal.x - self.start.x) / cMin],
- [(self.goal.y - self.start.y) / cMin], [0]])
-
- etheta = math.atan2(a1[1], a1[0])
- # first column of idenity matrix transposed
+ c_min = math.hypot(self.start.x - self.goal.x,
+ self.start.y - self.goal.y)
+ x_center = np.array([[(self.start.x + self.goal.x) / 2.0],
+ [(self.start.y + self.goal.y) / 2.0], [0]])
+ a1 = np.array([[(self.goal.x - self.start.x) / c_min],
+ [(self.goal.y - self.start.y) / c_min], [0]])
+
+ e_theta = math.atan2(a1[1, 0], a1[0, 0])
+ # first column of identity matrix transposed
id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3)
- M = a1 @ id1_t
- U, S, Vh = np.linalg.svd(M, 1, 1)
- C = np.dot(np.dot(U, np.diag(
- [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh)
-
- for i in range(self.maxIter):
- # Sample space is defined by cBest
- # cMin is the minimum distance between the start point and the goal
- # xCenter is the midpoint between the start and the goal
- # cBest changes when a new path is found
-
- rnd = self.informed_sample(cBest, cMin, xCenter, C)
- nind = self.getNearestListIndex(self.nodeList, rnd)
- nearestNode = self.nodeList[nind]
+ m = a1 @ id1_t
+ u, s, vh = np.linalg.svd(m, True, True)
+ c = u @ np.diag(
+ [1.0, 1.0,
+ np.linalg.det(u) * np.linalg.det(np.transpose(vh))]) @ vh
+
+ for i in range(self.max_iter):
+ # Sample space is defined by c_best
+ # c_min is the minimum distance between the start point and
+ # the goal x_center is the midpoint between the start and the
+ # goal c_best changes when a new path is found
+
+ rnd = self.informed_sample(c_best, c_min, x_center, c)
+ n_ind = self.get_nearest_list_index(self.node_list, rnd)
+ nearest_node = self.node_list[n_ind]
# steer
- theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x)
- newNode = self.getNewNode(theta, nind, nearestNode)
- d = self.lineCost(nearestNode, newNode)
-
- isCollision = self.__CollisionCheck(newNode, self.obstacleList)
- isCollisionEx = self.check_collision_extend(nearestNode, theta, d)
-
- if isCollision and isCollisionEx:
- nearInds = self.findNearNodes(newNode)
- newNode = self.chooseParent(newNode, nearInds)
-
- self.nodeList.append(newNode)
- self.rewire(newNode, nearInds)
-
- if self.isNearGoal(newNode):
- solutionSet.add(newNode)
- lastIndex = len(self.nodeList) - 1
- tempPath = self.getFinalCourse(lastIndex)
- tempPathLen = self.getPathLen(tempPath)
- if tempPathLen < pathLen:
- path = tempPath
- cBest = tempPathLen
-
+ theta = math.atan2(rnd[1] - nearest_node.y,
+ rnd[0] - nearest_node.x)
+ new_node = self.get_new_node(theta, n_ind, nearest_node)
+ d = self.line_cost(nearest_node, new_node)
+
+ no_collision = self.check_collision(nearest_node, theta, d)
+
+ if no_collision:
+ near_inds = self.find_near_nodes(new_node)
+ new_node = self.choose_parent(new_node, near_inds)
+
+ self.node_list.append(new_node)
+ self.rewire(new_node, near_inds)
+
+ if self.is_near_goal(new_node):
+ if self.check_segment_collision(new_node.x, new_node.y,
+ self.goal.x, self.goal.y):
+ solution_set.add(new_node)
+ last_index = len(self.node_list) - 1
+ temp_path = self.get_final_course(last_index)
+ temp_path_len = self.get_path_len(temp_path)
+ if temp_path_len < c_best:
+ path = temp_path
+ c_best = temp_path_len
if animation:
- self.drawGraph(xCenter=xCenter,
- cBest=cBest, cMin=cMin,
- etheta=etheta, rnd=rnd)
+ self.draw_graph(x_center=x_center, c_best=c_best, c_min=c_min,
+ e_theta=e_theta, rnd=rnd)
return path
- def chooseParent(self, newNode, nearInds):
- if len(nearInds) == 0:
- return newNode
+ def choose_parent(self, new_node, near_inds):
+ if len(near_inds) == 0:
+ return new_node
- dList = []
- for i in nearInds:
- dx = newNode.x - self.nodeList[i].x
- dy = newNode.y - self.nodeList[i].y
- d = math.sqrt(dx ** 2 + dy ** 2)
+ d_list = []
+ for i in near_inds:
+ dx = new_node.x - self.node_list[i].x
+ dy = new_node.y - self.node_list[i].y
+ d = math.hypot(dx, dy)
theta = math.atan2(dy, dx)
- if self.check_collision_extend(self.nodeList[i], theta, d):
- dList.append(self.nodeList[i].cost + d)
+ if self.check_collision(self.node_list[i], theta, d):
+ d_list.append(self.node_list[i].cost + d)
else:
- dList.append(float('inf'))
-
- minCost = min(dList)
- minInd = nearInds[dList.index(minCost)]
-
- if minCost == float('inf'):
- print("mincost is inf")
- return newNode
-
- newNode.cost = minCost
- newNode.parent = minInd
-
- return newNode
-
- def findNearNodes(self, newNode):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- dlist = [(node.x - newNode.x) ** 2
- + (node.y - newNode.y) ** 2 for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def informed_sample(self, cMax, cMin, xCenter, C):
- if cMax < float('inf'):
- r = [cMax / 2.0,
- math.sqrt(cMax**2 - cMin**2) / 2.0,
- math.sqrt(cMax**2 - cMin**2) / 2.0]
- L = np.diag(r)
- xBall = self.sampleUnitBall()
- rnd = np.dot(np.dot(C, L), xBall) + xCenter
+ d_list.append(float('inf'))
+
+ min_cost = min(d_list)
+ min_ind = near_inds[d_list.index(min_cost)]
+
+ if min_cost == float('inf'):
+ print("min cost is inf")
+ return new_node
+
+ new_node.cost = min_cost
+ new_node.parent = min_ind
+
+ return new_node
+
+ def find_near_nodes(self, new_node):
+ n_node = len(self.node_list)
+ r = 50.0 * math.sqrt(math.log(n_node) / n_node)
+ d_list = [(node.x - new_node.x) ** 2 + (node.y - new_node.y) ** 2 for
+ node in self.node_list]
+ near_inds = [d_list.index(i) for i in d_list if i <= r ** 2]
+ return near_inds
+
+ def informed_sample(self, c_max, c_min, x_center, c):
+ if c_max < float('inf'):
+ r = [c_max / 2.0, math.sqrt(c_max ** 2 - c_min ** 2) / 2.0,
+ math.sqrt(c_max ** 2 - c_min ** 2) / 2.0]
+ rl = np.diag(r)
+ x_ball = self.sample_unit_ball()
+ rnd = np.dot(np.dot(c, rl), x_ball) + x_center
rnd = [rnd[(0, 0)], rnd[(1, 0)]]
else:
- rnd = self.sampleFreeSpace()
+ rnd = self.sample_free_space()
return rnd
- def sampleUnitBall(self):
+ @staticmethod
+ def sample_unit_ball():
a = random.random()
b = random.random()
@@ -159,143 +167,155 @@ def sampleUnitBall(self):
b * math.sin(2 * math.pi * a / b))
return np.array([[sample[0]], [sample[1]], [0]])
- def sampleFreeSpace(self):
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand)]
+ def sample_free_space(self):
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = [random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand)]
else:
rnd = [self.goal.x, self.goal.y]
return rnd
- def getPathLen(self, path):
- pathLen = 0
+ @staticmethod
+ def get_path_len(path):
+ path_len = 0
for i in range(1, len(path)):
node1_x = path[i][0]
node1_y = path[i][1]
node2_x = path[i - 1][0]
node2_y = path[i - 1][1]
- pathLen += math.sqrt((node1_x - node2_x)
- ** 2 + (node1_y - node2_y)**2)
-
- return pathLen
-
- def lineCost(self, node1, node2):
- return math.sqrt((node1.x - node2.x)**2 + (node1.y - node2.y)**2)
-
- def getNearestListIndex(self, nodes, rnd):
- dList = [(node.x - rnd[0])**2
- + (node.y - rnd[1])**2 for node in nodes]
- minIndex = dList.index(min(dList))
- return minIndex
-
- def __CollisionCheck(self, newNode, obstacleList):
- for (ox, oy, size) in obstacleList:
- dx = ox - newNode.x
- dy = oy - newNode.y
- d = dx * dx + dy * dy
- if d <= 1.1 * size**2:
- return False # collision
-
- return True # safe
-
- def getNewNode(self, theta, nind, nearestNode):
- newNode = copy.deepcopy(nearestNode)
-
- newNode.x += self.expandDis * math.cos(theta)
- newNode.y += self.expandDis * math.sin(theta)
+ path_len += math.hypot(node1_x - node2_x, node1_y - node2_y)
- newNode.cost += self.expandDis
- newNode.parent = nind
- return newNode
-
- def isNearGoal(self, node):
- d = self.lineCost(node, self.goal)
- if d < self.expandDis:
- return True
- return False
+ return path_len
- def rewire(self, newNode, nearInds):
- nnode = len(self.nodeList)
- for i in nearInds:
- nearNode = self.nodeList[i]
+ @staticmethod
+ def line_cost(node1, node2):
+ return math.hypot(node1.x - node2.x, node1.y - node2.y)
- d = math.sqrt((nearNode.x - newNode.x)**2
- + (nearNode.y - newNode.y)**2)
+ @staticmethod
+ def get_nearest_list_index(nodes, rnd):
+ d_list = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1]) ** 2 for node in
+ nodes]
+ min_index = d_list.index(min(d_list))
+ return min_index
- scost = newNode.cost + d
+ def get_new_node(self, theta, n_ind, nearest_node):
+ new_node = copy.deepcopy(nearest_node)
- if nearNode.cost > scost:
- theta = math.atan2(newNode.y - nearNode.y,
- newNode.x - nearNode.x)
- if self.check_collision_extend(nearNode, theta, d):
- nearNode.parent = nnode - 1
- nearNode.cost = scost
+ new_node.x += self.expand_dis * math.cos(theta)
+ new_node.y += self.expand_dis * math.sin(theta)
- def check_collision_extend(self, nearNode, theta, d):
- tmpNode = copy.deepcopy(nearNode)
+ new_node.cost += self.expand_dis
+ new_node.parent = n_ind
+ return new_node
- for i in range(int(d / self.expandDis)):
- tmpNode.x += self.expandDis * math.cos(theta)
- tmpNode.y += self.expandDis * math.sin(theta)
- if not self.__CollisionCheck(tmpNode, self.obstacleList):
- return False
+ def is_near_goal(self, node):
+ d = self.line_cost(node, self.goal)
+ if d < self.expand_dis:
+ return True
+ return False
+ def rewire(self, new_node, near_inds):
+ n_node = len(self.node_list)
+ for i in near_inds:
+ near_node = self.node_list[i]
+
+ d = math.hypot(near_node.x - new_node.x, near_node.y - new_node.y)
+
+ s_cost = new_node.cost + d
+
+ if near_node.cost > s_cost:
+ theta = math.atan2(new_node.y - near_node.y,
+ new_node.x - near_node.x)
+ if self.check_collision(near_node, theta, d):
+ near_node.parent = n_node - 1
+ near_node.cost = s_cost
+
+ @staticmethod
+ def distance_squared_point_to_segment(v, w, p):
+ # Return minimum distance between line segment vw and point p
+ if np.array_equal(v, w):
+ return (p - v).dot(p - v) # v == w case
+ l2 = (w - v).dot(w - v) # i.e. |w-v|^2 - avoid a sqrt
+ # Consider the line extending the segment,
+ # parameterized as v + t (w - v).
+ # We find projection of point p onto the line.
+ # It falls where t = [(p-v) . (w-v)] / |w-v|^2
+ # We clamp t from [0,1] to handle points outside the segment vw.
+ t = max(0, min(1, (p - v).dot(w - v) / l2))
+ projection = v + t * (w - v) # Projection falls on the segment
+ return (p - projection).dot(p - projection)
+
+ def check_segment_collision(self, x1, y1, x2, y2):
+ for (ox, oy, size) in self.obstacle_list:
+ dd = self.distance_squared_point_to_segment(
+ np.array([x1, y1]), np.array([x2, y2]), np.array([ox, oy]))
+ if dd <= size ** 2:
+ return False # collision
return True
- def getFinalCourse(self, lastIndex):
+ def check_collision(self, near_node, theta, d):
+ tmp_node = copy.deepcopy(near_node)
+ end_x = tmp_node.x + math.cos(theta) * d
+ end_y = tmp_node.y + math.sin(theta) * d
+ return self.check_segment_collision(tmp_node.x, tmp_node.y,
+ end_x, end_y)
+
+ def get_final_course(self, last_index):
path = [[self.goal.x, self.goal.y]]
- while self.nodeList[lastIndex].parent is not None:
- node = self.nodeList[lastIndex]
+ while self.node_list[last_index].parent is not None:
+ node = self.node_list[last_index]
path.append([node.x, node.y])
- lastIndex = node.parent
+ last_index = node.parent
path.append([self.start.x, self.start.y])
return path
- def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None):
-
+ def draw_graph(self, x_center=None, c_best=None, c_min=None, e_theta=None,
+ rnd=None):
plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event', lambda event:
+ [exit(0) if event.key == 'escape' else None])
if rnd is not None:
plt.plot(rnd[0], rnd[1], "^k")
- if cBest != float('inf'):
- self.plot_ellipse(xCenter, cBest, cMin, etheta)
+ if c_best != float('inf'):
+ self.plot_ellipse(x_center, c_best, c_min, e_theta)
- for node in self.nodeList:
+ for node in self.node_list:
if node.parent is not None:
if node.x or node.y is not None:
- plt.plot([node.x, self.nodeList[node.parent].x], [
- node.y, self.nodeList[node.parent].y], "-g")
+ plt.plot([node.x, self.node_list[node.parent].x],
+ [node.y, self.node_list[node.parent].y], "-g")
- for (ox, oy, size) in self.obstacleList:
+ for (ox, oy, size) in self.obstacle_list:
plt.plot(ox, oy, "ok", ms=30 * size)
plt.plot(self.start.x, self.start.y, "xr")
plt.plot(self.goal.x, self.goal.y, "xr")
- plt.axis([-2, 15, -2, 15])
+ plt.axis([self.min_rand, self.max_rand, self.min_rand, self.max_rand])
plt.grid(True)
plt.pause(0.01)
- def plot_ellipse(self, xCenter, cBest, cMin, etheta): # pragma: no cover
-
- a = math.sqrt(cBest**2 - cMin**2) / 2.0
- b = cBest / 2.0
- angle = math.pi / 2.0 - etheta
- cx = xCenter[0]
- cy = xCenter[1]
+ @staticmethod
+ def plot_ellipse(x_center, c_best, c_min, e_theta): # pragma: no cover
+ a = math.sqrt(c_best ** 2 - c_min ** 2) / 2.0
+ b = c_best / 2.0
+ angle = math.pi / 2.0 - e_theta
+ cx = x_center[0]
+ cy = x_center[1]
t = np.arange(0, 2 * math.pi + 0.1, 0.1)
x = [a * math.cos(it) for it in t]
y = [b * math.sin(it) for it in t]
- R = np.array([[math.cos(angle), math.sin(angle)],
- [-math.sin(angle), math.cos(angle)]])
- fx = R @ np.array([x, y])
+ fx = rot_mat_2d(-angle) @ np.array([x, y])
px = np.array(fx[0, :] + cx).flatten()
py = np.array(fx[1, :] + cy).flatten()
plt.plot(cx, cy, "xc")
plt.plot(px, py, "--c")
-class Node():
+class Node:
def __init__(self, x, y):
self.x = x
@@ -308,24 +328,18 @@ def main():
print("Start informed rrt star planning")
# create obstacles
- obstacleList = [
- (5, 5, 0.5),
- (9, 6, 1),
- (7, 5, 1),
- (1, 5, 1),
- (3, 6, 1),
- (7, 9, 1)
- ]
+ obstacle_list = [(5, 5, 0.5), (9, 6, 1), (7, 5, 1), (1, 5, 1), (3, 6, 1),
+ (7, 9, 1)]
# Set params
- rrt = InformedRRTStar(start=[0, 0], goal=[5, 10],
- randArea=[-2, 15], obstacleList=obstacleList)
- path = rrt.InformedRRTStarSearch(animation=show_animation)
+ rrt = InformedRRTStar(start=[0, 0], goal=[5, 10], rand_area=[-2, 15],
+ obstacle_list=obstacle_list)
+ path = rrt.informed_rrt_star_search(animation=show_animation)
print("Done!!")
# Plot path
if show_animation:
- rrt.drawGraph()
+ rrt.draw_graph()
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
plt.grid(True)
plt.pause(0.01)
@@ -333,4 +347,4 @@ def main():
if __name__ == '__main__':
- main()
\ No newline at end of file
+ main()
diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py
deleted file mode 100644
index fef1020e5b..0000000000
--- a/PathPlanning/LQRPlanner/LQRplanner.py
+++ /dev/null
@@ -1,141 +0,0 @@
-"""
-
-LQR local path planning
-
-author: Atsushi Sakai (@Atsushi_twi)
-
-"""
-
-import matplotlib.pyplot as plt
-import numpy as np
-import scipy.linalg as la
-import math
-import random
-
-show_animation = True
-
-MAX_TIME = 100.0 # Maximum simulation time
-DT = 0.1 # Time tick
-
-
-def LQRplanning(sx, sy, gx, gy):
-
- rx, ry = [sx], [sy]
-
- x = np.array([sx - gx, sy - gy]).reshape(2, 1) # State vector
-
- # Linear system model
- A, B = get_system_model()
-
- found_path = False
-
- time = 0.0
- while time <= MAX_TIME:
- time += DT
-
- u = LQR_control(A, B, x)
-
- x = A @ x + B @ u
-
- rx.append(x[0, 0] + gx)
- ry.append(x[1, 0] + gy)
-
- d = math.sqrt((gx - rx[-1])**2 + (gy - ry[-1])**2)
- if d <= 0.1:
- # print("Goal!!")
- found_path = True
- break
-
- # animation
- if show_animation: # pragma: no cover
- plt.plot(sx, sy, "or")
- plt.plot(gx, gy, "ob")
- plt.plot(rx, ry, "-r")
- plt.axis("equal")
- plt.pause(1.0)
-
- if not found_path:
- print("Cannot found path")
- return [], []
-
- return rx, ry
-
-
-def solve_DARE(A, B, Q, R):
- """
- solve a discrete time_Algebraic Riccati equation (DARE)
- """
- X = Q
- maxiter = 150
- eps = 0.01
-
- for i in range(maxiter):
- Xn = A.T * X * A - A.T * X * B * \
- la.inv(R + B.T * X * B) * B.T * X * A + Q
- if (abs(Xn - X)).max() < eps:
- break
- X = Xn
-
- return Xn
-
-
-def dlqr(A, B, Q, R):
- """Solve the discrete time lqr controller.
- x[k+1] = A x[k] + B u[k]
- cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k]
- # ref Bertsekas, p.151
- """
-
- # first, try to solve the ricatti equation
- X = solve_DARE(A, B, Q, R)
-
- # compute the LQR gain
- K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A)
-
- eigVals, eigVecs = la.eig(A - B @ K)
-
- return K, X, eigVals
-
-
-def get_system_model():
-
- A = np.array([[DT, 1.0],
- [0.0, DT]])
- B = np.array([0.0, 1.0]).reshape(2, 1)
-
- return A, B
-
-
-def LQR_control(A, B, x):
-
- Kopt, X, ev = dlqr(A, B, np.eye(2), np.eye(1))
-
- u = -Kopt @ x
-
- return u
-
-
-def main():
- print(__file__ + " start!!")
-
- ntest = 10 # number of goal
- area = 100.0 # sampling area
-
- for i in range(ntest):
- sx = 6.0
- sy = 6.0
- gx = random.uniform(-area, area)
- gy = random.uniform(-area, area)
-
- rx, ry = LQRplanning(sx, sy, gx, gy)
-
- if show_animation: # pragma: no cover
- plt.plot(sx, sy, "or")
- plt.plot(gx, gy, "ob")
- plt.plot(rx, ry, "-r")
- plt.axis("equal")
- plt.pause(1.0)
-
-
-if __name__ == '__main__':
- main()
diff --git a/PathPlanning/LQRPlanner/lqr_planner.py b/PathPlanning/LQRPlanner/lqr_planner.py
new file mode 100644
index 0000000000..0f58f93ea3
--- /dev/null
+++ b/PathPlanning/LQRPlanner/lqr_planner.py
@@ -0,0 +1,146 @@
+"""
+
+LQR local path planning
+
+author: Atsushi Sakai (@Atsushi_twi)
+
+"""
+
+import math
+import random
+
+import matplotlib.pyplot as plt
+import numpy as np
+import scipy.linalg as la
+
+SHOW_ANIMATION = True
+
+
+class LQRPlanner:
+
+ def __init__(self):
+ self.MAX_TIME = 100.0 # Maximum simulation time
+ self.DT = 0.1 # Time tick
+ self.GOAL_DIST = 0.1
+ self.MAX_ITER = 150
+ self.EPS = 0.01
+
+ def lqr_planning(self, sx, sy, gx, gy, show_animation=True):
+
+ rx, ry = [sx], [sy]
+
+ x = np.array([sx - gx, sy - gy]).reshape(2, 1) # State vector
+
+ # Linear system model
+ A, B = self.get_system_model()
+
+ found_path = False
+
+ time = 0.0
+ while time <= self.MAX_TIME:
+ time += self.DT
+
+ u = self.lqr_control(A, B, x)
+
+ x = A @ x + B @ u
+
+ rx.append(x[0, 0] + gx)
+ ry.append(x[1, 0] + gy)
+
+ d = math.hypot(gx - rx[-1], gy - ry[-1])
+ if d <= self.GOAL_DIST:
+ found_path = True
+ break
+
+ # animation
+ if show_animation: # pragma: no cover
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(sx, sy, "or")
+ plt.plot(gx, gy, "ob")
+ plt.plot(rx, ry, "-r")
+ plt.axis("equal")
+ plt.pause(1.0)
+
+ if not found_path:
+ print("Cannot found path")
+ return [], []
+
+ return rx, ry
+
+ def solve_dare(self, A, B, Q, R):
+ """
+ solve a discrete time_Algebraic Riccati equation (DARE)
+ """
+ X, Xn = Q, Q
+
+ for i in range(self.MAX_ITER):
+ Xn = A.T * X * A - A.T * X * B * \
+ la.inv(R + B.T * X * B) * B.T * X * A + Q
+ if (abs(Xn - X)).max() < self.EPS:
+ break
+ X = Xn
+
+ return Xn
+
+ def dlqr(self, A, B, Q, R):
+ """Solve the discrete time lqr controller.
+ x[k+1] = A x[k] + B u[k]
+ cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k]
+ # ref Bertsekas, p.151
+ """
+
+ # first, try to solve the ricatti equation
+ X = self.solve_dare(A, B, Q, R)
+
+ # compute the LQR gain
+ K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A)
+
+ eigValues = la.eigvals(A - B @ K)
+
+ return K, X, eigValues
+
+ def get_system_model(self):
+
+ A = np.array([[self.DT, 1.0],
+ [0.0, self.DT]])
+ B = np.array([0.0, 1.0]).reshape(2, 1)
+
+ return A, B
+
+ def lqr_control(self, A, B, x):
+
+ Kopt, X, ev = self.dlqr(A, B, np.eye(2), np.eye(1))
+
+ u = -Kopt @ x
+
+ return u
+
+
+def main():
+ print(__file__ + " start!!")
+
+ ntest = 10 # number of goal
+ area = 100.0 # sampling area
+
+ lqr_planner = LQRPlanner()
+
+ for i in range(ntest):
+ sx = 6.0
+ sy = 6.0
+ gx = random.uniform(-area, area)
+ gy = random.uniform(-area, area)
+
+ rx, ry = lqr_planner.lqr_planning(sx, sy, gx, gy, show_animation=SHOW_ANIMATION)
+
+ if SHOW_ANIMATION: # pragma: no cover
+ plt.plot(sx, sy, "or")
+ plt.plot(gx, gy, "ob")
+ plt.plot(rx, ry, "-r")
+ plt.axis("equal")
+ plt.pause(1.0)
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py
index 0fb25fe421..0ed08123ea 100644
--- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py
+++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py
@@ -5,116 +5,166 @@
author: AtsushiSakai(@Atsushi_twi)
"""
-
-import matplotlib.pyplot as plt
-import numpy as np
import copy
import math
import random
+import matplotlib.pyplot as plt
+import numpy as np
import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../LQRPlanner/")
-
-try:
- import LQRplanner
-except:
- raise
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+from LQRPlanner.lqr_planner import LQRPlanner
+from RRTStar.rrt_star import RRTStar
show_animation = True
-LQRplanner.show_animation = False
-STEP_SIZE = 0.05 # step size of local path
-XYTH = 0.5 # [m] acceptance xy distance in final paths
-
-
-class RRT():
+class LQRRRTStar(RRTStar):
"""
- Class for RRT Planning
+ Class for RRT star planning with LQR planning
"""
- def __init__(self, start, goal, obstacleList, randArea,
- goalSampleRate=10, maxIter=200):
+ def __init__(self, start, goal, obstacle_list, rand_area,
+ goal_sample_rate=10,
+ max_iter=200,
+ connect_circle_dist=50.0,
+ step_size=0.2,
+ robot_radius=0.0,
+ ):
"""
Setting Parameter
start:Start Position [x,y]
goal:Goal Position [x,y]
obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
+ randArea:Random Sampling Area [min,max]
+ robot_radius: robot body modeled as circle with given radius
"""
- self.start = Node(start[0], start[1])
- self.end = Node(goal[0], goal[1])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def planning(self, animation=True):
+ self.start = self.Node(start[0], start[1])
+ self.end = self.Node(goal[0], goal[1])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+ self.connect_circle_dist = connect_circle_dist
+
+ self.curvature = 1.0
+ self.goal_xy_th = 0.5
+ self.step_size = step_size
+ self.robot_radius = robot_radius
+
+ self.lqr_planner = LQRPlanner()
+
+ def planning(self, animation=True, search_until_max_iter=True):
"""
- Pathplanning
+ RRT Star planning
animation: flag for animation on or off
"""
- self.nodeList = [self.start]
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.get_nearest_index(self.nodeList, rnd)
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind], rnd)
+
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ near_indexes = self.find_near_nodes(new_node)
+ new_node = self.choose_parent(new_node, near_indexes)
+ if new_node:
+ self.node_list.append(new_node)
+ self.rewire(new_node, near_indexes)
+
+ if animation and i % 5 == 0:
+ self.draw_graph(rnd)
- newNode = self.steer(rnd, nind)
- if newNode is None:
- continue
+ if (not search_until_max_iter) and new_node: # check reaching the goal
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
- if self.check_collision(newNode, self.obstacleList):
- nearinds = self.find_near_nodes(newNode)
- newNode = self.choose_parent(newNode, nearinds)
- if newNode is None:
- continue
- self.nodeList.append(newNode)
- self.rewire(newNode, nearinds)
+ print("reached max iteration")
- if animation and i % 5 == 0:
- self.draw_graph(rnd=rnd)
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
+ else:
+ print("Cannot find path")
+
+ return None
+
+ def draw_graph(self, rnd=None):
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
+
+ for (ox, oy, size) in self.obstacle_list:
+ plt.plot(ox, oy, "ok", ms=30 * size)
+
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis([-2, 15, -2, 15])
+ plt.grid(True)
+ plt.pause(0.01)
+
+ def search_best_goal_node(self):
+ dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list]
+ goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.goal_xy_th]
- # generate coruse
- lastIndex = self.get_best_last_index()
- if lastIndex is None:
+ if not goal_inds:
return None
- path = self.gen_final_course(lastIndex)
- return path
- def choose_parent(self, newNode, nearinds):
- if not nearinds:
- return newNode
+ min_cost = min([self.node_list[i].cost for i in goal_inds])
+ for i in goal_inds:
+ if self.node_list[i].cost == min_cost:
+ return i
+
+ return None
- dlist = []
- for i in nearinds:
- tNode = self.steer(newNode, i)
- if tNode is None:
- continue
+ def calc_new_cost(self, from_node, to_node):
- if self.check_collision(tNode, self.obstacleList):
- dlist.append(tNode.cost)
- else:
- dlist.append(float("inf"))
+ wx, wy = self.lqr_planner.lqr_planning(
+ from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False)
- mincost = min(dlist)
- minind = nearinds[dlist.index(mincost)]
+ px, py, course_lengths = self.sample_path(wx, wy, self.step_size)
- if mincost == float("inf"):
- print("mincost is inf")
- return newNode
+ if not course_lengths:
+ return float("inf")
- newNode = self.steer(newNode, minind)
+ return from_node.cost + sum(course_lengths)
- return newNode
+ def get_random_node(self):
+
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = self.Node(random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand)
+ )
+ else: # goal point sampling
+ rnd = self.Node(self.end.x, self.end.y)
- def pi_2_pi(self, angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return rnd
+
+ def generate_final_course(self, goal_index):
+ print("final")
+ path = [[self.end.x, self.end.y]]
+ node = self.node_list[goal_index]
+ while node.parent:
+ for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
+ path.append([ix, iy])
+ node = node.parent
+ path.append([self.start.x, self.start.y])
+ return path
def sample_path(self, wx, wy, step):
@@ -129,160 +179,30 @@ def sample_path(self, wx, wy, step):
dx = np.diff(px)
dy = np.diff(py)
- clen = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)]
+ clen = [math.hypot(idx, idy) for (idx, idy) in zip(dx, dy)]
return px, py, clen
- def steer(self, rnd, nind):
-
- nearestNode = self.nodeList[nind]
+ def steer(self, from_node, to_node):
- wx, wy = LQRplanner.LQRplanning(
- nearestNode.x, nearestNode.y, rnd.x, rnd.y)
+ wx, wy = self.lqr_planner.lqr_planning(
+ from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False)
- px, py, clen = self.sample_path(wx, wy, STEP_SIZE)
+ px, py, course_lens = self.sample_path(wx, wy, self.step_size)
if px is None:
return None
- newNode = copy.deepcopy(nearestNode)
+ newNode = copy.deepcopy(from_node)
newNode.x = px[-1]
newNode.y = py[-1]
-
newNode.path_x = px
newNode.path_y = py
- newNode.cost += sum([abs(c) for c in clen])
- newNode.parent = nind
+ newNode.cost += sum([abs(c) for c in course_lens])
+ newNode.parent = from_node
return newNode
- def get_random_point(self):
-
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand),
- random.uniform(-math.pi, math.pi)
- ]
- else: # goal point sampling
- rnd = [self.end.x, self.end.y]
-
- node = Node(rnd[0], rnd[1])
-
- return node
-
- def get_best_last_index(self):
- # print("get_best_last_index")
-
- goalinds = []
- for (i, node) in enumerate(self.nodeList):
- if self.calc_dist_to_goal(node.x, node.y) <= XYTH:
- goalinds.append(i)
-
- if not goalinds:
- return None
-
- mincost = min([self.nodeList[i].cost for i in goalinds])
- for i in goalinds:
- if self.nodeList[i].cost == mincost:
- return i
-
- return None
-
- def gen_final_course(self, goalind):
- path = [[self.end.x, self.end.y]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
- for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
- path.append([ix, iy])
- goalind = node.parent
- path.append([self.start.x, self.start.y])
- return path
-
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def find_near_nodes(self, newNode):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- dlist = [(node.x - newNode.x) ** 2
- + (node.y - newNode.y) ** 2
- for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def rewire(self, newNode, nearinds):
-
- nnode = len(self.nodeList)
-
- for i in nearinds:
- nearNode = self.nodeList[i]
- tNode = self.steer(nearNode, nnode - 1)
- if tNode is None:
- continue
-
- obstacleOK = self.check_collision(tNode, self.obstacleList)
- imporveCost = nearNode.cost > tNode.cost
-
- if obstacleOK and imporveCost:
- # print("rewire")
- self.nodeList[i] = tNode
-
- def draw_graph(self, rnd=None):
- plt.clf()
- if rnd is not None:
- plt.plot(rnd.x, rnd.y, "^k")
-
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot(node.path_x, node.path_y, "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- plt.plot(self.start.x, self.start.y, "or")
- plt.plot(self.end.x, self.end.y, "or")
-
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- def get_nearest_index(self, nodeList, rnd):
- dlist = [(node.x - rnd.x) ** 2
- + (node.y - rnd.y) ** 2
- for node in nodeList]
- minind = dlist.index(min(dlist))
-
- return minind
-
- def check_collision(self, node, obstacleList):
-
- px = np.array(node.path_x)
- py = np.array(node.path_y)
-
- for (ox, oy, size) in obstacleList:
- dx = ox - px
- dy = oy - py
- d = dx ** 2 + dy ** 2
- dmin = min(d)
- if dmin <= size ** 2:
- return False # collision
-
- return True # safe
-
-
-class Node():
- """
- RRT Node
- """
-
- def __init__(self, x, y):
- self.x = x
- self.y = y
- self.path_x = []
- self.path_y = []
- self.cost = 0.0
- self.parent = None
-
def main(maxIter=200):
print("Start " + __file__)
@@ -301,14 +221,14 @@ def main(maxIter=200):
start = [0.0, 0.0]
goal = [6.0, 7.0]
- rrt = RRT(start, goal, randArea=[-2.0, 15.0],
- obstacleList=obstacleList,
- maxIter=maxIter)
- path = rrt.planning(animation=show_animation)
+ lqr_rrt_star = LQRRRTStar(start, goal,
+ obstacleList,
+ [-2.0, 15.0])
+ path = lqr_rrt_star.planning(animation=show_animation)
# Draw final path
if show_animation: # pragma: no cover
- rrt.draw_graph()
+ lqr_rrt_star.draw_graph()
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
plt.grid(True)
plt.pause(0.001)
diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py
new file mode 100644
index 0000000000..4c3b32f280
--- /dev/null
+++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py
@@ -0,0 +1,110 @@
+"""
+
+Lookup Table generation for model predictive trajectory generator
+
+author: Atsushi Sakai
+
+"""
+import sys
+import pathlib
+path_planning_dir = pathlib.Path(__file__).parent.parent
+sys.path.append(str(path_planning_dir))
+
+from matplotlib import pyplot as plt
+import numpy as np
+import math
+
+from ModelPredictiveTrajectoryGenerator import trajectory_generator,\
+ motion_model
+
+
+def calc_states_list(max_yaw=np.deg2rad(-30.0)):
+
+ x = np.arange(10.0, 30.0, 5.0)
+ y = np.arange(0.0, 20.0, 2.0)
+ yaw = np.arange(-max_yaw, max_yaw, max_yaw)
+
+ states = []
+ for iyaw in yaw:
+ for iy in y:
+ for ix in x:
+ states.append([ix, iy, iyaw])
+ print("n_state:", len(states))
+
+ return states
+
+
+def search_nearest_one_from_lookup_table(tx, ty, tyaw, lookup_table):
+ mind = float("inf")
+ minid = -1
+
+ for (i, table) in enumerate(lookup_table):
+
+ dx = tx - table[0]
+ dy = ty - table[1]
+ dyaw = tyaw - table[2]
+ d = math.sqrt(dx ** 2 + dy ** 2 + dyaw ** 2)
+ if d <= mind:
+ minid = i
+ mind = d
+
+ # print(minid)
+
+ return lookup_table[minid]
+
+
+def save_lookup_table(file_name, table):
+ np.savetxt(file_name, np.array(table),
+ fmt='%s', delimiter=",", header="x,y,yaw,s,km,kf", comments="")
+
+ print("lookup table file is saved as " + file_name)
+
+
+def generate_lookup_table():
+ states = calc_states_list(max_yaw=np.deg2rad(-30.0))
+ k0 = 0.0
+
+ # x, y, yaw, s, km, kf
+ lookup_table = [[1.0, 0.0, 0.0, 1.0, 0.0, 0.0]]
+
+ for state in states:
+ best_p = search_nearest_one_from_lookup_table(
+ state[0], state[1], state[2], lookup_table)
+
+ target = motion_model.State(x=state[0], y=state[1], yaw=state[2])
+ init_p = np.array(
+ [np.hypot(state[0], state[1]), best_p[4], best_p[5]]).reshape(3, 1)
+
+ x, y, yaw, p = trajectory_generator.optimize_trajectory(target,
+ k0, init_p)
+
+ if x is not None:
+ print("find good path")
+ lookup_table.append(
+ [x[-1], y[-1], yaw[-1], float(p[0, 0]), float(p[1, 0]), float(p[2, 0])])
+
+ print("finish lookup table generation")
+
+ save_lookup_table("lookup_table.csv", lookup_table)
+
+ for table in lookup_table:
+ x_c, y_c, yaw_c = motion_model.generate_trajectory(
+ table[3], table[4], table[5], k0)
+ plt.plot(x_c, y_c, "-r")
+ x_c, y_c, yaw_c = motion_model.generate_trajectory(
+ table[3], -table[4], -table[5], k0)
+ plt.plot(x_c, y_c, "-r")
+
+ plt.grid(True)
+ plt.axis("equal")
+ plt.show()
+
+ print("Done")
+
+
+def main():
+ generate_lookup_table()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py
deleted file mode 100644
index c57a05da57..0000000000
--- a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py
+++ /dev/null
@@ -1,114 +0,0 @@
-"""
-
-Lookup Table generation for model predictive trajectory generator
-
-author: Atsushi Sakai
-
-"""
-from matplotlib import pyplot as plt
-import numpy as np
-import math
-import model_predictive_trajectory_generator as planner
-import motion_model
-import pandas as pd
-
-
-def calc_states_list():
- maxyaw = np.deg2rad(-30.0)
-
- x = np.arange(10.0, 30.0, 5.0)
- y = np.arange(0.0, 20.0, 2.0)
- yaw = np.arange(-maxyaw, maxyaw, maxyaw)
-
- states = []
- for iyaw in yaw:
- for iy in y:
- for ix in x:
- states.append([ix, iy, iyaw])
- print("nstate:", len(states))
-
- return states
-
-
-def search_nearest_one_from_lookuptable(tx, ty, tyaw, lookuptable):
- mind = float("inf")
- minid = -1
-
- for (i, table) in enumerate(lookuptable):
-
- dx = tx - table[0]
- dy = ty - table[1]
- dyaw = tyaw - table[2]
- d = math.sqrt(dx ** 2 + dy ** 2 + dyaw ** 2)
- if d <= mind:
- minid = i
- mind = d
-
- # print(minid)
-
- return lookuptable[minid]
-
-
-def save_lookup_table(fname, table):
- mt = np.array(table)
- print(mt)
- # save csv
- df = pd.DataFrame()
- df["x"] = mt[:, 0]
- df["y"] = mt[:, 1]
- df["yaw"] = mt[:, 2]
- df["s"] = mt[:, 3]
- df["km"] = mt[:, 4]
- df["kf"] = mt[:, 5]
- df.to_csv(fname, index=None)
-
- print("lookup table file is saved as " + fname)
-
-
-def generate_lookup_table():
- states = calc_states_list()
- k0 = 0.0
-
- # x, y, yaw, s, km, kf
- lookuptable = [[1.0, 0.0, 0.0, 1.0, 0.0, 0.0]]
-
- for state in states:
- bestp = search_nearest_one_from_lookuptable(
- state[0], state[1], state[2], lookuptable)
-
- target = motion_model.State(x=state[0], y=state[1], yaw=state[2])
- init_p = np.array(
- [math.sqrt(state[0] ** 2 + state[1] ** 2), bestp[4], bestp[5]]).reshape(3, 1)
-
- x, y, yaw, p = planner.optimize_trajectory(target, k0, init_p)
-
- if x is not None:
- print("find good path")
- lookuptable.append(
- [x[-1], y[-1], yaw[-1], float(p[0]), float(p[1]), float(p[2])])
-
- print("finish lookup table generation")
-
- save_lookup_table("lookuptable.csv", lookuptable)
-
- for table in lookuptable:
- xc, yc, yawc = motion_model.generate_trajectory(
- table[3], table[4], table[5], k0)
- plt.plot(xc, yc, "-r")
- xc, yc, yawc = motion_model.generate_trajectory(
- table[3], -table[4], -table[5], k0)
- plt.plot(xc, yc, "-r")
-
- plt.grid(True)
- plt.axis("equal")
- plt.show()
-
- print("Done")
-
-
-def main():
- generate_lookup_table()
-
-
-if __name__ == '__main__':
- main()
diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py
index bb66d1fb54..5ef6d2e23f 100644
--- a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py
+++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py
@@ -1,10 +1,11 @@
import math
import numpy as np
-import scipy.interpolate
+from scipy.interpolate import interp1d
+from utils.angle import angle_mod
# motion parameter
L = 1.0 # wheel base
-ds = 0.1 # course distanse
+ds = 0.1 # course distance
v = 10.0 / 3.6 # velocity [m/s]
@@ -18,11 +19,10 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def update(state, v, delta, dt, L):
-
state.v = v
state.x = state.x + state.v * math.cos(state.yaw) * dt
state.y = state.y + state.v * math.sin(state.yaw) * dt
@@ -33,13 +33,20 @@ def update(state, v, delta, dt, L):
def generate_trajectory(s, km, kf, k0):
-
n = s / ds
time = s / v # [s]
+
+ if isinstance(time, type(np.array([]))):
+ time = time[0]
+ if isinstance(km, type(np.array([]))):
+ km = km[0]
+ if isinstance(kf, type(np.array([]))):
+ kf = kf[0]
+
tk = np.array([0.0, time / 2.0, time])
kk = np.array([k0, km, kf])
t = np.arange(0.0, time, time / n)
- fkp = scipy.interpolate.interp1d(tk, kk, kind="quadratic")
+ fkp = interp1d(tk, kk, kind="quadratic")
kp = [fkp(ti) for ti in t]
dt = float(time / n)
@@ -59,13 +66,22 @@ def generate_trajectory(s, km, kf, k0):
def generate_last_state(s, km, kf, k0):
-
n = s / ds
time = s / v # [s]
+
+ if isinstance(n, type(np.array([]))):
+ n = n[0]
+ if isinstance(time, type(np.array([]))):
+ time = time[0]
+ if isinstance(km, type(np.array([]))):
+ km = km[0]
+ if isinstance(kf, type(np.array([]))):
+ kf = kf[0]
+
tk = np.array([0.0, time / 2.0, time])
kk = np.array([k0, km, kf])
t = np.arange(0.0, time, time / n)
- fkp = scipy.interpolate.interp1d(tk, kk, kind="quadratic")
+ fkp = interp1d(tk, kk, kind="quadratic")
kp = [fkp(ti) for ti in t]
dt = time / n
diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py
similarity index 88%
rename from PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py
rename to PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py
index ad3bb11f2a..6084fc1a07 100644
--- a/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py
+++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py
@@ -6,14 +6,19 @@
"""
-import numpy as np
-import matplotlib.pyplot as plt
import math
-import motion_model
+import matplotlib.pyplot as plt
+import numpy as np
+import sys
+import pathlib
+path_planning_dir = pathlib.Path(__file__).parent.parent
+sys.path.append(str(path_planning_dir))
+
+import ModelPredictiveTrajectoryGenerator.motion_model as motion_model
# optimization parameter
max_iter = 100
-h = np.array([0.5, 0.02, 0.02]).T # parameter sampling distance
+h: np.ndarray = np.array([0.5, 0.02, 0.02]).T # parameter sampling distance
cost_th = 0.1
show_animation = True
@@ -37,7 +42,7 @@ def calc_diff(target, x, y, yaw):
return d
-def calc_J(target, p, h, k0):
+def calc_j(target, p, h, k0):
xp, yp, yawp = motion_model.generate_last_state(
p[0, 0] + h[0], p[1, 0], p[2, 0], k0)
dp = calc_diff(target, [xp], [yp], [yawp])
@@ -68,7 +73,6 @@ def calc_J(target, p, h, k0):
def selection_learning_param(dp, p, k0, target):
-
mincost = float("inf")
mina = 1.0
maxa = 2.0
@@ -102,7 +106,7 @@ def show_trajectory(target, xc, yc): # pragma: no cover
def optimize_trajectory(target, k0, p):
for i in range(max_iter):
- xc, yc, yawc = motion_model.generate_trajectory(p[0], p[1], p[2], k0)
+ xc, yc, yawc = motion_model.generate_trajectory(p[0, 0], p[1, 0], p[2, 0], k0)
dc = np.array(calc_diff(target, xc, yc, yawc)).reshape(3, 1)
cost = np.linalg.norm(dc)
@@ -110,7 +114,7 @@ def optimize_trajectory(target, k0, p):
print("path is ok cost is:" + str(cost))
break
- J = calc_J(target, p, h, k0)
+ J = calc_j(target, p, h, k0)
try:
dp = - np.linalg.inv(J) @ dc
except np.linalg.linalg.LinAlgError:
@@ -131,7 +135,7 @@ def optimize_trajectory(target, k0, p):
return xc, yc, yawc, p
-def test_optimize_trajectory(): # pragma: no cover
+def optimize_trajectory_demo(): # pragma: no cover
# target = motion_model.State(x=5.0, y=2.0, yaw=np.deg2rad(00.0))
target = motion_model.State(x=5.0, y=2.0, yaw=np.deg2rad(90.0))
@@ -151,7 +155,7 @@ def test_optimize_trajectory(): # pragma: no cover
def main(): # pragma: no cover
print(__file__ + " start!!")
- test_optimize_trajectory()
+ optimize_trajectory_demo()
if __name__ == '__main__':
diff --git a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py
index 1e918fb158..603a9d16cf 100644
--- a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py
+++ b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py
@@ -4,11 +4,12 @@
author: Atsushi Sakai (@Atsushi_twi)
-Ref:
+Reference:
https://www.cs.cmu.edu/~motionplanning/lecture/Chap4-Potential-Field_howie.pdf
"""
+from collections import deque
import numpy as np
import matplotlib.pyplot as plt
@@ -16,15 +17,17 @@
KP = 5.0 # attractive potential gain
ETA = 100.0 # repulsive potential gain
AREA_WIDTH = 30.0 # potential area width [m]
+# the number of previous positions used to check oscillations
+OSCILLATIONS_DETECTION_LENGTH = 3
show_animation = True
-def calc_potential_field(gx, gy, ox, oy, reso, rr):
- minx = min(ox) - AREA_WIDTH / 2.0
- miny = min(oy) - AREA_WIDTH / 2.0
- maxx = max(ox) + AREA_WIDTH / 2.0
- maxy = max(oy) + AREA_WIDTH / 2.0
+def calc_potential_field(gx, gy, ox, oy, reso, rr, sx, sy):
+ minx = min(min(ox), sx, gx) - AREA_WIDTH / 2.0
+ miny = min(min(oy), sy, gy) - AREA_WIDTH / 2.0
+ maxx = max(max(ox), sx, gx) + AREA_WIDTH / 2.0
+ maxy = max(max(oy), sy, gy) + AREA_WIDTH / 2.0
xw = int(round((maxx - minx) / reso))
yw = int(round((maxy - miny) / reso))
@@ -84,10 +87,26 @@ def get_motion_model():
return motion
+def oscillations_detection(previous_ids, ix, iy):
+ previous_ids.append((ix, iy))
+
+ if (len(previous_ids) > OSCILLATIONS_DETECTION_LENGTH):
+ previous_ids.popleft()
+
+ # check if contains any duplicates by copying into a set
+ previous_ids_set = set()
+ for index in previous_ids:
+ if index in previous_ids_set:
+ return True
+ else:
+ previous_ids_set.add(index)
+ return False
+
+
def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr):
# calc potential field
- pmap, minx, miny = calc_potential_field(gx, gy, ox, oy, reso, rr)
+ pmap, minx, miny = calc_potential_field(gx, gy, ox, oy, reso, rr, sx, sy)
# search path
d = np.hypot(sx - gx, sy - gy)
@@ -98,19 +117,25 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr):
if show_animation:
draw_heatmap(pmap)
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(ix, iy, "*k")
plt.plot(gix, giy, "*m")
rx, ry = [sx], [sy]
motion = get_motion_model()
+ previous_ids = deque()
+
while d >= reso:
minp = float("inf")
minix, miniy = -1, -1
for i, _ in enumerate(motion):
inx = int(ix + motion[i][0])
iny = int(iy + motion[i][1])
- if inx >= len(pmap) or iny >= len(pmap[0]):
+ if inx >= len(pmap) or iny >= len(pmap[0]) or inx < 0 or iny < 0:
p = float("inf") # outside area
+ print("outside potential!")
else:
p = pmap[inx][iny]
if minp > p:
@@ -125,6 +150,10 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr):
rx.append(xp)
ry.append(yp)
+ if (oscillations_detection(previous_ids, ix, iy)):
+ print("Oscillation detected at ({},{})!".format(ix, iy))
+ break
+
if show_animation:
plt.plot(ix, iy, ".r")
plt.pause(0.01)
diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py
index 351232d849..8bacfd5d19 100644
--- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py
+++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py
@@ -1,16 +1,15 @@
"""
-Probablistic Road Map (PRM) Planner
+Probabilistic Road Map (PRM) Planner
author: Atsushi Sakai (@Atsushi_twi)
"""
-import random
import math
import numpy as np
-import scipy.spatial
import matplotlib.pyplot as plt
+from scipy.spatial import KDTree
# parameter
N_SAMPLE = 500 # number of sample_points
@@ -25,129 +24,104 @@ class Node:
Node class for dijkstra search
"""
- def __init__(self, x, y, cost, pind):
+ def __init__(self, x, y, cost, parent_index):
self.x = x
self.y = y
self.cost = cost
- self.pind = pind
+ self.parent_index = parent_index
def __str__(self):
- return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
+ return str(self.x) + "," + str(self.y) + "," +\
+ str(self.cost) + "," + str(self.parent_index)
-class KDTree:
+def prm_planning(start_x, start_y, goal_x, goal_y,
+ obstacle_x_list, obstacle_y_list, robot_radius, *, rng=None):
"""
- Nearest neighbor search class with KDTree
+ Run probabilistic road map planning
+
+ :param start_x: start x position
+ :param start_y: start y position
+ :param goal_x: goal x position
+ :param goal_y: goal y position
+ :param obstacle_x_list: obstacle x positions
+ :param obstacle_y_list: obstacle y positions
+ :param robot_radius: robot radius
+ :param rng: (Optional) Random generator
+ :return:
"""
+ obstacle_kd_tree = KDTree(np.vstack((obstacle_x_list, obstacle_y_list)).T)
- def __init__(self, data):
- # store kd-tree
- self.tree = scipy.spatial.cKDTree(data)
-
- def search(self, inp, k=1):
- """
- Search NN
-
- inp: input data, single frame or multi frame
-
- """
-
- if len(inp.shape) >= 2: # multi input
- index = []
- dist = []
-
- for i in inp.T:
- idist, iindex = self.tree.query(i, k=k)
- index.append(iindex)
- dist.append(idist)
-
- return index, dist
-
- dist, index = self.tree.query(inp, k=k)
- return index, dist
-
- def search_in_distance(self, inp, r):
- """
- find points with in a distance r
- """
-
- index = self.tree.query_ball_point(inp, r)
- return index
-
-
-def PRM_planning(sx, sy, gx, gy, ox, oy, rr):
-
- obkdtree = KDTree(np.vstack((ox, oy)).T)
-
- sample_x, sample_y = sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree)
+ sample_x, sample_y = sample_points(start_x, start_y, goal_x, goal_y,
+ robot_radius,
+ obstacle_x_list, obstacle_y_list,
+ obstacle_kd_tree, rng)
if show_animation:
plt.plot(sample_x, sample_y, ".b")
- road_map = generate_roadmap(sample_x, sample_y, rr, obkdtree)
+ road_map = generate_road_map(sample_x, sample_y,
+ robot_radius, obstacle_kd_tree)
rx, ry = dijkstra_planning(
- sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y)
+ start_x, start_y, goal_x, goal_y, road_map, sample_x, sample_y)
return rx, ry
-def is_collision(sx, sy, gx, gy, rr, okdtree):
+def is_collision(sx, sy, gx, gy, rr, obstacle_kd_tree):
x = sx
y = sy
dx = gx - sx
dy = gy - sy
yaw = math.atan2(gy - sy, gx - sx)
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
if d >= MAX_EDGE_LEN:
return True
D = rr
- nstep = round(d / D)
+ n_step = round(d / D)
- for i in range(nstep):
- idxs, dist = okdtree.search(np.array([x, y]).reshape(2, 1))
- if dist[0] <= rr:
+ for i in range(n_step):
+ dist, _ = obstacle_kd_tree.query([x, y])
+ if dist <= rr:
return True # collision
x += D * math.cos(yaw)
y += D * math.sin(yaw)
# goal point check
- idxs, dist = okdtree.search(np.array([gx, gy]).reshape(2, 1))
- if dist[0] <= rr:
+ dist, _ = obstacle_kd_tree.query([gx, gy])
+ if dist <= rr:
return True # collision
return False # OK
-def generate_roadmap(sample_x, sample_y, rr, obkdtree):
+def generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree):
"""
Road map generation
sample_x: [m] x positions of sampled points
sample_y: [m] y positions of sampled points
- rr: Robot Radius[m]
- obkdtree: KDTree object of obstacles
+ robot_radius: Robot Radius[m]
+ obstacle_kd_tree: KDTree object of obstacles
"""
road_map = []
- nsample = len(sample_x)
- skdtree = KDTree(np.vstack((sample_x, sample_y)).T)
+ n_sample = len(sample_x)
+ sample_kd_tree = KDTree(np.vstack((sample_x, sample_y)).T)
- for (i, ix, iy) in zip(range(nsample), sample_x, sample_y):
+ for (i, ix, iy) in zip(range(n_sample), sample_x, sample_y):
- index, dists = skdtree.search(
- np.array([ix, iy]).reshape(2, 1), k=nsample)
- inds = index[0]
+ dists, indexes = sample_kd_tree.query([ix, iy], k=n_sample)
edge_id = []
- # print(index)
- for ii in range(1, len(inds)):
- nx = sample_x[inds[ii]]
- ny = sample_y[inds[ii]]
+ for ii in range(1, len(indexes)):
+ nx = sample_x[indexes[ii]]
+ ny = sample_y[indexes[ii]]
- if not is_collision(ix, iy, nx, ny, rr, obkdtree):
- edge_id.append(inds[ii])
+ if not is_collision(ix, iy, nx, ny, rr, obstacle_kd_tree):
+ edge_id.append(indexes[ii])
if len(edge_id) >= N_KNN:
break
@@ -159,85 +133,89 @@ def generate_roadmap(sample_x, sample_y, rr, obkdtree):
return road_map
-def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y):
+def dijkstra_planning(sx, sy, gx, gy, road_map, sample_x, sample_y):
"""
- sx: start x position [m]
- sy: start y position [m]
- gx: goal x position [m]
- gy: goal y position [m]
- ox: x position list of Obstacles [m]
- oy: y position list of Obstacles [m]
- rr: robot radius [m]
+ s_x: start x position [m]
+ s_y: start y position [m]
+ goal_x: goal x position [m]
+ goal_y: goal y position [m]
+ obstacle_x_list: x position list of Obstacles [m]
+ obstacle_y_list: y position list of Obstacles [m]
+ robot_radius: robot radius [m]
road_map: ??? [m]
sample_x: ??? [m]
sample_y: ??? [m]
-
+
@return: Two lists of path coordinates ([x1, x2, ...], [y1, y2, ...]), empty list when no path was found
"""
- nstart = Node(sx, sy, 0.0, -1)
- ngoal = Node(gx, gy, 0.0, -1)
+ start_node = Node(sx, sy, 0.0, -1)
+ goal_node = Node(gx, gy, 0.0, -1)
- openset, closedset = dict(), dict()
- openset[len(road_map) - 2] = nstart
+ open_set, closed_set = dict(), dict()
+ open_set[len(road_map) - 2] = start_node
path_found = True
-
+
while True:
- if not openset:
+ if not open_set:
print("Cannot find path")
path_found = False
break
- c_id = min(openset, key=lambda o: openset[o].cost)
- current = openset[c_id]
+ c_id = min(open_set, key=lambda o: open_set[o].cost)
+ current = open_set[c_id]
# show graph
- if show_animation and len(closedset.keys()) % 2 == 0:
+ if show_animation and len(closed_set.keys()) % 2 == 0:
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(current.x, current.y, "xg")
plt.pause(0.001)
if c_id == (len(road_map) - 1):
print("goal is found!")
- ngoal.pind = current.pind
- ngoal.cost = current.cost
+ goal_node.parent_index = current.parent_index
+ goal_node.cost = current.cost
break
# Remove the item from the open set
- del openset[c_id]
+ del open_set[c_id]
# Add it to the closed set
- closedset[c_id] = current
+ closed_set[c_id] = current
# expand search grid based on motion model
for i in range(len(road_map[c_id])):
n_id = road_map[c_id][i]
dx = sample_x[n_id] - current.x
dy = sample_y[n_id] - current.y
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
node = Node(sample_x[n_id], sample_y[n_id],
current.cost + d, c_id)
- if n_id in closedset:
+ if n_id in closed_set:
continue
# Otherwise if it is already in the open set
- if n_id in openset:
- if openset[n_id].cost > node.cost:
- openset[n_id].cost = node.cost
- openset[n_id].pind = c_id
+ if n_id in open_set:
+ if open_set[n_id].cost > node.cost:
+ open_set[n_id].cost = node.cost
+ open_set[n_id].parent_index = c_id
else:
- openset[n_id] = node
-
+ open_set[n_id] = node
+
if path_found is False:
return [], []
# generate final course
- rx, ry = [ngoal.x], [ngoal.y]
- pind = ngoal.pind
- while pind != -1:
- n = closedset[pind]
+ rx, ry = [goal_node.x], [goal_node.y]
+ parent_index = goal_node.parent_index
+ while parent_index != -1:
+ n = closed_set[parent_index]
rx.append(n.x)
ry.append(n.y)
- pind = n.pind
+ parent_index = n.parent_index
return rx, ry
@@ -252,21 +230,24 @@ def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover
[sample_y[i], sample_y[ind]], "-k")
-def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree):
- maxx = max(ox)
- maxy = max(oy)
- minx = min(ox)
- miny = min(oy)
+def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree, rng):
+ max_x = max(ox)
+ max_y = max(oy)
+ min_x = min(ox)
+ min_y = min(oy)
sample_x, sample_y = [], []
+ if rng is None:
+ rng = np.random.default_rng()
+
while len(sample_x) <= N_SAMPLE:
- tx = (random.random() * (maxx - minx)) + minx
- ty = (random.random() * (maxy - miny)) + miny
+ tx = (rng.random() * (max_x - min_x)) + min_x
+ ty = (rng.random() * (max_y - min_y)) + min_y
- index, dist = obkdtree.search(np.array([tx, ty]).reshape(2, 1))
+ dist, index = obstacle_kd_tree.query([tx, ty])
- if dist[0] >= rr:
+ if dist >= rr:
sample_x.append(tx)
sample_y.append(ty)
@@ -278,7 +259,7 @@ def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree):
return sample_x, sample_y
-def main():
+def main(rng=None):
print(__file__ + " start!!")
# start and goal position
@@ -292,20 +273,20 @@ def main():
oy = []
for i in range(60):
- ox.append(i)
+ ox.append(float(i))
oy.append(0.0)
for i in range(60):
ox.append(60.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(61):
- ox.append(i)
+ ox.append(float(i))
oy.append(60.0)
for i in range(61):
ox.append(0.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(40):
ox.append(20.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(40):
ox.append(40.0)
oy.append(60.0 - i)
@@ -317,12 +298,13 @@ def main():
plt.grid(True)
plt.axis("equal")
- rx, ry = PRM_planning(sx, sy, gx, gy, ox, oy, robot_size)
+ rx, ry = prm_planning(sx, sy, gx, gy, ox, oy, robot_size, rng=rng)
assert rx, 'Cannot found path'
if show_animation:
plt.plot(rx, ry, "-r")
+ plt.pause(0.001)
plt.show()
diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py
index e2411d2bcb..86f9f662da 100644
--- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py
+++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py
@@ -1,19 +1,20 @@
"""
-Quinitc Polynomials Planner
+Quintic Polynomials Planner
author: Atsushi Sakai (@Atsushi_twi)
-Ref:
+Reference:
-- [Local Path Planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/)
+- [Local Path planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/)
"""
-import numpy as np
-import matplotlib.pyplot as plt
import math
+import matplotlib.pyplot as plt
+import numpy as np
+
# parameter
MAX_T = 100.0 # maximum time to the goal [s]
MIN_T = 5.0 # minimum time to the goal[s]
@@ -21,27 +22,20 @@
show_animation = True
-class quinic_polynomial:
-
- def __init__(self, xs, vxs, axs, xe, vxe, axe, T):
-
- # calc coefficient of quinic polynomial
- self.xs = xs
- self.vxs = vxs
- self.axs = axs
- self.xe = xe
- self.vxe = vxe
- self.axe = axe
+class QuinticPolynomial:
+ def __init__(self, xs, vxs, axs, xe, vxe, axe, time):
+ # calc coefficient of quintic polynomial
+ # See jupyter notebook document for derivation of this equation.
self.a0 = xs
self.a1 = vxs
self.a2 = axs / 2.0
- A = np.array([[T**3, T**4, T**5],
- [3 * T ** 2, 4 * T ** 3, 5 * T ** 4],
- [6 * T, 12 * T ** 2, 20 * T ** 3]])
- b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2,
- vxe - self.a1 - 2 * self.a2 * T,
+ A = np.array([[time ** 3, time ** 4, time ** 5],
+ [3 * time ** 2, 4 * time ** 3, 5 * time ** 4],
+ [6 * time, 12 * time ** 2, 20 * time ** 3]])
+ b = np.array([xe - self.a0 - self.a1 * time - self.a2 * time ** 2,
+ vxe - self.a1 - 2 * self.a2 * time,
axe - 2 * self.a2])
x = np.linalg.solve(A, b)
@@ -50,36 +44,36 @@ def __init__(self, xs, vxs, axs, xe, vxe, axe, T):
self.a5 = x[2]
def calc_point(self, t):
- xt = self.a0 + self.a1 * t + self.a2 * t**2 + \
- self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5
+ xt = self.a0 + self.a1 * t + self.a2 * t ** 2 + \
+ self.a3 * t ** 3 + self.a4 * t ** 4 + self.a5 * t ** 5
return xt
def calc_first_derivative(self, t):
xt = self.a1 + 2 * self.a2 * t + \
- 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4
+ 3 * self.a3 * t ** 2 + 4 * self.a4 * t ** 3 + 5 * self.a5 * t ** 4
return xt
def calc_second_derivative(self, t):
- xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3
+ xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t ** 2 + 20 * self.a5 * t ** 3
return xt
def calc_third_derivative(self, t):
- xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2
+ xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t ** 2
return xt
-def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt):
+def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt):
"""
- quinic polynomial planner
+ quintic polynomial planner
input
- sx: start x position [m]
- sy: start y position [m]
- syaw: start yaw angle [rad]
+ s_x: start x position [m]
+ s_y: start y position [m]
+ s_yaw: start yaw angle [rad]
sa: start accel [m/ss]
gx: goal x position [m]
gy: goal y position [m]
@@ -109,9 +103,11 @@ def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_a
axg = ga * math.cos(gyaw)
ayg = ga * math.sin(gyaw)
+ time, rx, ry, ryaw, rv, ra, rj = [], [], [], [], [], [], []
+
for T in np.arange(MIN_T, MAX_T, MIN_T):
- xqp = quinic_polynomial(sx, vxs, axs, gx, vxg, axg, T)
- yqp = quinic_polynomial(sy, vys, ays, gy, vyg, ayg, T)
+ xqp = QuinticPolynomial(sx, vxs, axs, gx, vxg, axg, T)
+ yqp = QuinticPolynomial(sy, vys, ays, gy, vyg, ayg, T)
time, rx, ry, ryaw, rv, ra, rj = [], [], [], [], [], [], []
@@ -146,8 +142,11 @@ def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_a
break
if show_animation: # pragma: no cover
- for i, _ in enumerate(rx):
+ for i, _ in enumerate(time):
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.grid(True)
plt.axis("equal")
plot_arrow(sx, sy, syaw)
@@ -194,7 +193,7 @@ def main():
max_jerk = 0.5 # max jerk [m/sss]
dt = 0.1 # time tick [s]
- time, x, y, yaw, v, a, j = quinic_polynomials_planner(
+ time, x, y, yaw, v, a, j = quintic_polynomials_planner(
sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt)
if show_animation: # pragma: no cover
diff --git a/PathPlanning/RRT/__init__.py b/PathPlanning/RRT/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py
new file mode 100644
index 0000000000..e6dd9b648b
--- /dev/null
+++ b/PathPlanning/RRT/rrt.py
@@ -0,0 +1,291 @@
+"""
+
+Path planning Sample Code with Randomized Rapidly-Exploring Random Trees (RRT)
+
+author: AtsushiSakai(@Atsushi_twi)
+
+"""
+
+import math
+import random
+
+import matplotlib.pyplot as plt
+import numpy as np
+
+show_animation = True
+
+
+class RRT:
+ """
+ Class for RRT planning
+ """
+
+ class Node:
+ """
+ RRT Node
+ """
+
+ def __init__(self, x, y):
+ self.x = x
+ self.y = y
+ self.path_x = []
+ self.path_y = []
+ self.parent = None
+
+ class AreaBounds:
+
+ def __init__(self, area):
+ self.xmin = float(area[0])
+ self.xmax = float(area[1])
+ self.ymin = float(area[2])
+ self.ymax = float(area[3])
+
+
+ def __init__(self,
+ start,
+ goal,
+ obstacle_list,
+ rand_area,
+ expand_dis=3.0,
+ path_resolution=0.5,
+ goal_sample_rate=5,
+ max_iter=500,
+ play_area=None,
+ robot_radius=0.0,
+ ):
+ """
+ Setting Parameter
+
+ start:Start Position [x,y]
+ goal:Goal Position [x,y]
+ obstacleList:obstacle Positions [[x,y,size],...]
+ randArea:Random Sampling Area [min,max]
+ play_area:stay inside this area [xmin,xmax,ymin,ymax]
+ robot_radius: robot body modeled as circle with given radius
+
+ """
+ self.start = self.Node(start[0], start[1])
+ self.end = self.Node(goal[0], goal[1])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ if play_area is not None:
+ self.play_area = self.AreaBounds(play_area)
+ else:
+ self.play_area = None
+ self.expand_dis = expand_dis
+ self.path_resolution = path_resolution
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+ self.node_list = []
+ self.robot_radius = robot_radius
+
+ def planning(self, animation=True):
+ """
+ rrt path planning
+
+ animation: flag for animation on or off
+ """
+
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ rnd_node = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd_node)
+ nearest_node = self.node_list[nearest_ind]
+
+ new_node = self.steer(nearest_node, rnd_node, self.expand_dis)
+
+ if self.check_if_outside_play_area(new_node, self.play_area) and \
+ self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ self.node_list.append(new_node)
+
+ if animation and i % 5 == 0:
+ self.draw_graph(rnd_node)
+
+ if self.calc_dist_to_goal(self.node_list[-1].x,
+ self.node_list[-1].y) <= self.expand_dis:
+ final_node = self.steer(self.node_list[-1], self.end,
+ self.expand_dis)
+ if self.check_collision(
+ final_node, self.obstacle_list, self.robot_radius):
+ return self.generate_final_course(len(self.node_list) - 1)
+
+ if animation and i % 5:
+ self.draw_graph(rnd_node)
+
+ return None # cannot find path
+
+ def steer(self, from_node, to_node, extend_length=float("inf")):
+
+ new_node = self.Node(from_node.x, from_node.y)
+ d, theta = self.calc_distance_and_angle(new_node, to_node)
+
+ new_node.path_x = [new_node.x]
+ new_node.path_y = [new_node.y]
+
+ if extend_length > d:
+ extend_length = d
+
+ n_expand = math.floor(extend_length / self.path_resolution)
+
+ for _ in range(n_expand):
+ new_node.x += self.path_resolution * math.cos(theta)
+ new_node.y += self.path_resolution * math.sin(theta)
+ new_node.path_x.append(new_node.x)
+ new_node.path_y.append(new_node.y)
+
+ d, _ = self.calc_distance_and_angle(new_node, to_node)
+ if d <= self.path_resolution:
+ new_node.path_x.append(to_node.x)
+ new_node.path_y.append(to_node.y)
+ new_node.x = to_node.x
+ new_node.y = to_node.y
+
+ new_node.parent = from_node
+
+ return new_node
+
+ def generate_final_course(self, goal_ind):
+ path = [[self.end.x, self.end.y]]
+ node = self.node_list[goal_ind]
+ while node.parent is not None:
+ path.append([node.x, node.y])
+ node = node.parent
+ path.append([node.x, node.y])
+
+ return path
+
+ def calc_dist_to_goal(self, x, y):
+ dx = x - self.end.x
+ dy = y - self.end.y
+ return math.hypot(dx, dy)
+
+ def get_random_node(self):
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = self.Node(
+ random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand))
+ else: # goal point sampling
+ rnd = self.Node(self.end.x, self.end.y)
+ return rnd
+
+ def draw_graph(self, rnd=None):
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ if self.robot_radius > 0.0:
+ self.plot_circle(rnd.x, rnd.y, self.robot_radius, '-r')
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
+
+ for (ox, oy, size) in self.obstacle_list:
+ self.plot_circle(ox, oy, size)
+
+ if self.play_area is not None:
+ plt.plot([self.play_area.xmin, self.play_area.xmax,
+ self.play_area.xmax, self.play_area.xmin,
+ self.play_area.xmin],
+ [self.play_area.ymin, self.play_area.ymin,
+ self.play_area.ymax, self.play_area.ymax,
+ self.play_area.ymin],
+ "-k")
+
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis("equal")
+ plt.axis([self.min_rand, self.max_rand, self.min_rand, self.max_rand])
+ plt.grid(True)
+ plt.pause(0.01)
+
+ @staticmethod
+ def plot_circle(x, y, size, color="-b"): # pragma: no cover
+ deg = list(range(0, 360, 5))
+ deg.append(0)
+ xl = [x + size * math.cos(np.deg2rad(d)) for d in deg]
+ yl = [y + size * math.sin(np.deg2rad(d)) for d in deg]
+ plt.plot(xl, yl, color)
+
+ @staticmethod
+ def get_nearest_node_index(node_list, rnd_node):
+ dlist = [(node.x - rnd_node.x)**2 + (node.y - rnd_node.y)**2
+ for node in node_list]
+ minind = dlist.index(min(dlist))
+
+ return minind
+
+ @staticmethod
+ def check_if_outside_play_area(node, play_area):
+
+ if play_area is None:
+ return True # no play_area was defined, every pos should be ok
+
+ if node.x < play_area.xmin or node.x > play_area.xmax or \
+ node.y < play_area.ymin or node.y > play_area.ymax:
+ return False # outside - bad
+ else:
+ return True # inside - ok
+
+ @staticmethod
+ def check_collision(node, obstacleList, robot_radius):
+
+ if node is None:
+ return False
+
+ for (ox, oy, size) in obstacleList:
+ dx_list = [ox - x for x in node.path_x]
+ dy_list = [oy - y for y in node.path_y]
+ d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)]
+
+ if min(d_list) <= (size+robot_radius)**2:
+ return False # collision
+
+ return True # safe
+
+ @staticmethod
+ def calc_distance_and_angle(from_node, to_node):
+ dx = to_node.x - from_node.x
+ dy = to_node.y - from_node.y
+ d = math.hypot(dx, dy)
+ theta = math.atan2(dy, dx)
+ return d, theta
+
+
+def main(gx=6.0, gy=10.0):
+ print("start " + __file__)
+
+ # ====Search Path with RRT====
+ obstacleList = [(5, 5, 1), (3, 6, 2), (3, 8, 2), (3, 10, 2), (7, 5, 2),
+ (9, 5, 2), (8, 10, 1)] # [x, y, radius]
+ # Set Initial parameters
+ rrt = RRT(
+ start=[0, 0],
+ goal=[gx, gy],
+ rand_area=[-2, 15],
+ obstacle_list=obstacleList,
+ # play_area=[0, 10, 0, 14]
+ robot_radius=0.8
+ )
+ path = rrt.planning(animation=show_animation)
+
+ if path is None:
+ print("Cannot find path")
+ else:
+ print("found path!!")
+
+ # Draw final path
+ if show_animation:
+ rrt.draw_graph()
+ plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
+ plt.grid(True)
+ plt.pause(0.01) # Need for Mac
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/RRT/rrt_with_pathsmoothing.py b/PathPlanning/RRT/rrt_with_pathsmoothing.py
index 70dd55a327..ac68efe23f 100644
--- a/PathPlanning/RRT/rrt_with_pathsmoothing.py
+++ b/PathPlanning/RRT/rrt_with_pathsmoothing.py
@@ -1,170 +1,42 @@
"""
-Path Planning Sample Code with Randamized Rapidly-Exploring Random Trees (RRT)
+
+Path planning Sample Code with RRT with path smoothing
@author: AtsushiSakai(@Atsushi_twi)
"""
-import matplotlib.pyplot as plt
-import random
import math
-import copy
-import numpy as np
-
-show_animation = True
-
-
-class RRT():
- """
- Class for RRT Planning
- """
-
- def __init__(self, start, goal, obstacleList, randArea, expandDis=1.0, goalSampleRate=5, maxIter=500):
- """
- Setting Parameter
-
- start:Start Position [x,y]
- goal:Goal Position [x,y]
- obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
-
- """
- self.start = Node(start[0], start[1])
- self.end = Node(goal[0], goal[1])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.expandDis = expandDis
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=True):
- """
- Pathplanning
-
- animation: flag for animation on or off
- """
-
- self.nodeList = [self.start]
- while True:
- # Random Sampling
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand), random.uniform(
- self.minrand, self.maxrand)]
- else:
- rnd = [self.end.x, self.end.y]
-
- # Find nearest node
- nind = self.GetNearestListIndex(self.nodeList, rnd)
- # print(nind)
-
- # expand tree
- nearestNode = self.nodeList[nind]
- theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x)
-
- newNode = copy.deepcopy(nearestNode)
- newNode.x += self.expandDis * math.cos(theta)
- newNode.y += self.expandDis * math.sin(theta)
- newNode.parent = nind
-
- if not self.__CollisionCheck(newNode, self.obstacleList):
- continue
-
- self.nodeList.append(newNode)
-
- # check goal
- dx = newNode.x - self.end.x
- dy = newNode.y - self.end.y
- d = math.sqrt(dx * dx + dy * dy)
- if d <= self.expandDis:
- print("Goal!!")
- break
-
- if animation:
- self.DrawGraph(rnd)
-
- path = [[self.end.x, self.end.y]]
- lastIndex = len(self.nodeList) - 1
- while self.nodeList[lastIndex].parent is not None:
- node = self.nodeList[lastIndex]
- path.append([node.x, node.y])
- lastIndex = node.parent
- path.append([self.start.x, self.start.y])
-
- return path
-
- def DrawGraph(self, rnd=None):
- plt.clf()
- if rnd is not None:
- plt.plot(rnd[0], rnd[1], "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot([node.x, self.nodeList[node.parent].x], [
- node.y, self.nodeList[node.parent].y], "-g")
- for (x, y, size) in self.obstacleList:
- self.PlotCircle(x, y, size)
-
- plt.plot(self.start.x, self.start.y, "xr")
- plt.plot(self.end.x, self.end.y, "xr")
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- def PlotCircle(self, x, y, size):
- deg = list(range(0, 360, 5))
- deg.append(0)
- xl = [x + size * math.cos(np.deg2rad(d)) for d in deg]
- yl = [y + size * math.sin(np.deg2rad(d)) for d in deg]
- plt.plot(xl, yl, "-k")
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1])
- ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
- return minind
-
- def __CollisionCheck(self, node, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- dx = ox - node.x
- dy = oy - node.y
- d = math.sqrt(dx * dx + dy * dy)
- if d <= size:
- return False # collision
-
- return True # safe
-
+import random
+import matplotlib.pyplot as plt
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent))
-class Node():
- """
- RRT Node
- """
+from rrt import RRT
- def __init__(self, x, y):
- self.x = x
- self.y = y
- self.parent = None
+show_animation = True
-def GetPathLength(path):
+def get_path_length(path):
le = 0
for i in range(len(path) - 1):
dx = path[i + 1][0] - path[i][0]
dy = path[i + 1][1] - path[i][1]
- d = math.sqrt(dx * dx + dy * dy)
+ d = math.hypot(dx, dy)
le += d
return le
-def GetTargetPoint(path, targetL):
+def get_target_point(path, targetL):
le = 0
ti = 0
lastPairLen = 0
for i in range(len(path) - 1):
dx = path[i + 1][0] - path[i][0]
dy = path[i + 1][1] - path[i][1]
- d = math.sqrt(dx * dx + dy * dy)
+ d = math.hypot(dx, dy)
le += d
if le >= targetL:
ti = i - 1
@@ -172,55 +44,108 @@ def GetTargetPoint(path, targetL):
break
partRatio = (le - targetL) / lastPairLen
- # print(partRatio)
- # print((ti,len(path),path[ti],path[ti+1]))
x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio
y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio
- # print((x,y))
return [x, y, ti]
-def LineCollisionCheck(first, second, obstacleList):
- # Line Equation
+def is_point_collision(x, y, obstacle_list, robot_radius):
+ """
+ Check whether a single point collides with any obstacle.
+
+ This function calculates the Euclidean distance between the given point (x, y)
+ and each obstacle center. If the distance is less than or equal to the sum of
+ the obstacle's radius and the robot's radius, a collision is detected.
+
+ Args:
+ x (float): X-coordinate of the point to check.
+ y (float): Y-coordinate of the point to check.
+ obstacle_list (List[Tuple[float, float, float]]): List of obstacles defined as (ox, oy, radius).
+ robot_radius (float): Radius of the robot, used to inflate the obstacles.
- x1 = first[0]
- y1 = first[1]
- x2 = second[0]
- y2 = second[1]
+ Returns:
+ bool: True if the point is in collision with any obstacle, False otherwise.
+ """
+ for (ox, oy, obstacle_radius) in obstacle_list:
+ d = math.hypot(ox - x, oy - y)
+ if d <= obstacle_radius + robot_radius:
+ return True # Collided
+ return False
+
+
+def line_collision_check(first, second, obstacle_list, robot_radius=0.0, sample_step=0.2):
+ """
+ Check if the line segment between `first` and `second` collides with any obstacle.
+ Considers the robot_radius by inflating the obstacle size.
+
+ Args:
+ first (List[float]): Start point of the line [x, y]
+ second (List[float]): End point of the line [x, y]
+ obstacle_list (List[Tuple[float, float, float]]): Obstacles as (x, y, radius)
+ robot_radius (float): Radius of robot
+ sample_step (float): Distance between sampling points along the segment
+
+ Returns:
+ bool: True if collision-free, False otherwise
+ """
+ x1, y1 = first[0], first[1]
+ x2, y2 = second[0], second[1]
+
+ dx = x2 - x1
+ dy = y2 - y1
+ length = math.hypot(dx, dy)
- try:
- a = y2 - y1
- b = -(x2 - x1)
- c = y2 * (x2 - x1) - x2 * (y2 - y1)
- except ZeroDivisionError:
- return False
+ if length == 0:
+ # Degenerate case: point collision check
+ return not is_point_collision(x1, y1, obstacle_list, robot_radius)
- for (ox, oy, size) in obstacleList:
- d = abs(a * ox + b * oy + c) / (math.sqrt(a * a + b * b))
- if d <= (size):
- return False
+ steps = int(length / sample_step) + 1 # Sampling every sample_step along the segment
- # print("OK")
+ for i in range(steps + 1):
+ t = i / steps
+ x = x1 + t * dx
+ y = y1 + t * dy
- return True # OK
+ if is_point_collision(x, y, obstacle_list, robot_radius):
+ return False # Collision found
+ return True # Safe
-def PathSmoothing(path, maxIter, obstacleList):
- # print("PathSmoothing")
- le = GetPathLength(path)
+def path_smoothing(path, max_iter, obstacle_list, robot_radius=0.0):
+ """
+ Smooths a given path by iteratively replacing segments with shortcut connections,
+ while ensuring the new segments are collision-free.
+
+ The algorithm randomly picks two points along the original path and attempts to
+ connect them with a straight line. If the line does not collide with any obstacles
+ (considering the robot's radius), the intermediate path points between them are
+ replaced with the direct connection.
+
+ Args:
+ path (List[List[float]]): The original path as a list of [x, y] coordinates.
+ max_iter (int): Number of iterations for smoothing attempts.
+ obstacle_list (List[Tuple[float, float, float]]): List of obstacles represented as
+ (x, y, radius).
+ robot_radius (float, optional): Radius of the robot, used to inflate obstacle size
+ during collision checking. Defaults to 0.0.
+
+ Returns:
+ List[List[float]]: The smoothed path as a list of [x, y] coordinates.
+
+ Example:
+ >>> smoothed = path_smoothing(path, 1000, obstacle_list, robot_radius=0.5)
+ """
+ le = get_path_length(path)
- for i in range(maxIter):
+ for i in range(max_iter):
# Sample two points
pickPoints = [random.uniform(0, le), random.uniform(0, le)]
pickPoints.sort()
- # print(pickPoints)
- first = GetTargetPoint(path, pickPoints[0])
- # print(first)
- second = GetTargetPoint(path, pickPoints[1])
- # print(second)
+ first = get_target_point(path, pickPoints[0])
+ second = get_target_point(path, pickPoints[1])
if first[2] <= 0 or second[2] <= 0:
continue
@@ -232,7 +157,7 @@ def PathSmoothing(path, maxIter, obstacleList):
continue
# collision check
- if not LineCollisionCheck(first, second, obstacleList):
+ if not line_collision_check(first, second, obstacle_list, robot_radius):
continue
# Create New path
@@ -242,7 +167,7 @@ def PathSmoothing(path, maxIter, obstacleList):
newPath.append([second[0], second[1]])
newPath.extend(path[second[2] + 1:])
path = newPath
- le = GetPathLength(path)
+ le = get_path_length(path)
return path
@@ -257,22 +182,24 @@ def main():
(3, 10, 2),
(7, 5, 2),
(9, 5, 2)
- ] # [x,y,size]
- rrt = RRT(start=[0, 0], goal=[5, 10],
- randArea=[-2, 15], obstacleList=obstacleList)
- path = rrt.Planning(animation=show_animation)
+ ] # [x,y,radius]
+ rrt = RRT(start=[0, 0], goal=[6, 10],
+ rand_area=[-2, 15], obstacle_list=obstacleList,
+ robot_radius=0.3)
+ path = rrt.planning(animation=show_animation)
# Path smoothing
maxIter = 1000
- smoothedPath = PathSmoothing(path, maxIter, obstacleList)
+ smoothedPath = path_smoothing(path, maxIter, obstacleList,
+ robot_radius=rrt.robot_radius)
# Draw final path
if show_animation:
- rrt.DrawGraph()
+ rrt.draw_graph()
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
plt.plot([x for (x, y) in smoothedPath], [
- y for (x, y) in smoothedPath], '-b')
+ y for (x, y) in smoothedPath], '-c')
plt.grid(True)
plt.pause(0.01) # Need for Mac
diff --git a/PathPlanning/RRT/rrt_with_sobol_sampler.py b/PathPlanning/RRT/rrt_with_sobol_sampler.py
new file mode 100644
index 0000000000..06e0c04c68
--- /dev/null
+++ b/PathPlanning/RRT/rrt_with_sobol_sampler.py
@@ -0,0 +1,278 @@
+"""
+
+Path planning Sample Code with Randomized Rapidly-Exploring Random
+Trees with sobol low discrepancy sampler(RRTSobol).
+Sobol wiki https://en.wikipedia.org/wiki/Sobol_sequence
+
+The goal of low discrepancy samplers is to generate a sequence of points that
+optimizes a criterion called dispersion. Intuitively, the idea is to place
+samples to cover the exploration space in a way that makes the largest
+uncovered area be as small as possible. This generalizes of the idea of grid
+resolution. For a grid, the resolution may be selected by defining the step
+size for each axis. As the step size is decreased, the resolution increases.
+If a grid-based motion planning algorithm can increase the resolution
+arbitrarily, it becomes resolution complete. Dispersion can be considered as a
+powerful generalization of the notion of resolution.
+
+Taken from
+LaValle, Steven M. Planning algorithms. Cambridge university press, 2006.
+
+
+authors:
+ First implementation AtsushiSakai(@Atsushi_twi)
+ Sobol sampler Rafael A.
+Rojas (rafaelrojasmiliani@gmail.com)
+
+
+"""
+
+import math
+import random
+import sys
+import matplotlib.pyplot as plt
+import numpy as np
+
+from sobol import sobol_quasirand
+
+show_animation = True
+
+
+class RRTSobol:
+ """
+ Class for RRTSobol planning
+ """
+
+ class Node:
+ """
+ RRTSobol Node
+ """
+
+ def __init__(self, x, y):
+ self.x = x
+ self.y = y
+ self.path_x = []
+ self.path_y = []
+ self.parent = None
+
+ def __init__(self,
+ start,
+ goal,
+ obstacle_list,
+ rand_area,
+ expand_dis=3.0,
+ path_resolution=0.5,
+ goal_sample_rate=5,
+ max_iter=500,
+ robot_radius=0.0):
+ """
+ Setting Parameter
+
+ start:Start Position [x,y]
+ goal:Goal Position [x,y]
+ obstacle_list:obstacle Positions [[x,y,size],...]
+ randArea:Random Sampling Area [min,max]
+ robot_radius: robot body modeled as circle with given radius
+
+ """
+ self.start = self.Node(start[0], start[1])
+ self.end = self.Node(goal[0], goal[1])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.expand_dis = expand_dis
+ self.path_resolution = path_resolution
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+ self.node_list = []
+ self.sobol_inter_ = 0
+ self.robot_radius = robot_radius
+
+ def planning(self, animation=True):
+ """
+ rrt path planning
+
+ animation: flag for animation on or off
+ """
+
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ rnd_node = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd_node)
+ nearest_node = self.node_list[nearest_ind]
+
+ new_node = self.steer(nearest_node, rnd_node, self.expand_dis)
+
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ self.node_list.append(new_node)
+
+ if animation and i % 5 == 0:
+ self.draw_graph(rnd_node)
+
+ if self.calc_dist_to_goal(self.node_list[-1].x,
+ self.node_list[-1].y) <= self.expand_dis:
+ final_node = self.steer(self.node_list[-1], self.end,
+ self.expand_dis)
+ if self.check_collision(
+ final_node, self.obstacle_list, self.robot_radius):
+ return self.generate_final_course(len(self.node_list) - 1)
+
+ if animation and i % 5:
+ self.draw_graph(rnd_node)
+
+ return None # cannot find path
+
+ def steer(self, from_node, to_node, extend_length=float("inf")):
+
+ new_node = self.Node(from_node.x, from_node.y)
+ d, theta = self.calc_distance_and_angle(new_node, to_node)
+
+ new_node.path_x = [new_node.x]
+ new_node.path_y = [new_node.y]
+
+ if extend_length > d:
+ extend_length = d
+
+ n_expand = math.floor(extend_length / self.path_resolution)
+
+ for _ in range(n_expand):
+ new_node.x += self.path_resolution * math.cos(theta)
+ new_node.y += self.path_resolution * math.sin(theta)
+ new_node.path_x.append(new_node.x)
+ new_node.path_y.append(new_node.y)
+
+ d, _ = self.calc_distance_and_angle(new_node, to_node)
+ if d <= self.path_resolution:
+ new_node.path_x.append(to_node.x)
+ new_node.path_y.append(to_node.y)
+ new_node.x = to_node.x
+ new_node.y = to_node.y
+
+ new_node.parent = from_node
+
+ return new_node
+
+ def generate_final_course(self, goal_ind):
+ path = [[self.end.x, self.end.y]]
+ node = self.node_list[goal_ind]
+ while node.parent is not None:
+ path.append([node.x, node.y])
+ node = node.parent
+ path.append([node.x, node.y])
+
+ return path
+
+ def calc_dist_to_goal(self, x, y):
+ dx = x - self.end.x
+ dy = y - self.end.y
+ return math.hypot(dx, dy)
+
+ def get_random_node(self):
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rand_coordinates, n = sobol_quasirand(2, self.sobol_inter_)
+
+ rand_coordinates = self.min_rand + \
+ rand_coordinates*(self.max_rand - self.min_rand)
+ self.sobol_inter_ = n
+ rnd = self.Node(*rand_coordinates)
+
+ else: # goal point sampling
+ rnd = self.Node(self.end.x, self.end.y)
+ return rnd
+
+ def draw_graph(self, rnd=None):
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [sys.exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ if self.robot_radius >= 0.0:
+ self.plot_circle(rnd.x, rnd.y, self.robot_radius, '-r')
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
+
+ for (ox, oy, size) in self.obstacle_list:
+ self.plot_circle(ox, oy, size)
+
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis("equal")
+ plt.axis([-2, 15, -2, 15])
+ plt.grid(True)
+ plt.pause(0.01)
+
+ @staticmethod
+ def plot_circle(x, y, size, color="-b"): # pragma: no cover
+ deg = list(range(0, 360, 5))
+ deg.append(0)
+ xl = [x + size * math.cos(np.deg2rad(d)) for d in deg]
+ yl = [y + size * math.sin(np.deg2rad(d)) for d in deg]
+ plt.plot(xl, yl, color)
+
+ @staticmethod
+ def get_nearest_node_index(node_list, rnd_node):
+ dlist = [(node.x - rnd_node.x)**2 + (node.y - rnd_node.y)**2
+ for node in node_list]
+ minind = dlist.index(min(dlist))
+
+ return minind
+
+ @staticmethod
+ def check_collision(node, obstacle_list, robot_radius):
+
+ if node is None:
+ return False
+
+ for (ox, oy, size) in obstacle_list:
+ dx_list = [ox - x for x in node.path_x]
+ dy_list = [oy - y for y in node.path_y]
+ d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)]
+
+ if min(d_list) <= (size+robot_radius)**2:
+ return False # collision
+
+ return True # safe
+
+ @staticmethod
+ def calc_distance_and_angle(from_node, to_node):
+ dx = to_node.x - from_node.x
+ dy = to_node.y - from_node.y
+ d = math.hypot(dx, dy)
+ theta = math.atan2(dy, dx)
+ return d, theta
+
+
+def main(gx=6.0, gy=10.0):
+ print("start " + __file__)
+
+ # ====Search Path with RRTSobol====
+ obstacle_list = [(5, 5, 1), (3, 6, 2), (3, 8, 2), (3, 10, 2), (7, 5, 2),
+ (9, 5, 2), (8, 10, 1)] # [x, y, radius]
+ # Set Initial parameters
+ rrt = RRTSobol(
+ start=[0, 0],
+ goal=[gx, gy],
+ rand_area=[-2, 15],
+ obstacle_list=obstacle_list,
+ robot_radius=0.8)
+ path = rrt.planning(animation=show_animation)
+
+ if path is None:
+ print("Cannot find path")
+ else:
+ print("found path!!")
+
+ # Draw final path
+ if show_animation:
+ rrt.draw_graph()
+ plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
+ plt.grid(True)
+ plt.pause(0.01) # Need for Mac
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/RRT/simple_rrt.py b/PathPlanning/RRT/simple_rrt.py
deleted file mode 100644
index 3a40c672c4..0000000000
--- a/PathPlanning/RRT/simple_rrt.py
+++ /dev/null
@@ -1,173 +0,0 @@
-"""
-Path Planning Sample Code with Randamized Rapidly-Exploring Random Trees (RRT)
-
-author: AtsushiSakai(@Atsushi_twi)
-
-"""
-
-import matplotlib.pyplot as plt
-import random
-import math
-import copy
-
-show_animation = True
-
-
-class RRT():
- """
- Class for RRT Planning
- """
-
- def __init__(self, start, goal, obstacleList,
- randArea, expandDis=1.0, goalSampleRate=5, maxIter=500):
- """
- Setting Parameter
-
- start:Start Position [x,y]
- goal:Goal Position [x,y]
- obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
-
- """
- self.start = Node(start[0], start[1])
- self.end = Node(goal[0], goal[1])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.expandDis = expandDis
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=True):
- """
- Pathplanning
-
- animation: flag for animation on or off
- """
-
- self.nodeList = [self.start]
- while True:
- # Random Sampling
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand), random.uniform(
- self.minrand, self.maxrand)]
- else:
- rnd = [self.end.x, self.end.y]
-
- # Find nearest node
- nind = self.GetNearestListIndex(self.nodeList, rnd)
- # print(nind)
-
- # expand tree
- nearestNode = self.nodeList[nind]
- theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x)
-
- newNode = copy.deepcopy(nearestNode)
- newNode.x += self.expandDis * math.cos(theta)
- newNode.y += self.expandDis * math.sin(theta)
- newNode.parent = nind
-
- if not self.__CollisionCheck(newNode, self.obstacleList):
- continue
-
- self.nodeList.append(newNode)
- print("nNodelist:", len(self.nodeList))
-
- # check goal
- dx = newNode.x - self.end.x
- dy = newNode.y - self.end.y
- d = math.sqrt(dx * dx + dy * dy)
- if d <= self.expandDis:
- print("Goal!!")
- break
-
- if animation:
- self.DrawGraph(rnd)
-
- path = [[self.end.x, self.end.y]]
- lastIndex = len(self.nodeList) - 1
- while self.nodeList[lastIndex].parent is not None:
- node = self.nodeList[lastIndex]
- path.append([node.x, node.y])
- lastIndex = node.parent
- path.append([self.start.x, self.start.y])
-
- return path
-
- def DrawGraph(self, rnd=None): # pragma: no cover
- """
- Draw Graph
- """
- plt.clf()
- if rnd is not None:
- plt.plot(rnd[0], rnd[1], "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot([node.x, self.nodeList[node.parent].x], [
- node.y, self.nodeList[node.parent].y], "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- plt.plot(self.start.x, self.start.y, "xr")
- plt.plot(self.end.x, self.end.y, "xr")
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1])
- ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
- return minind
-
- def __CollisionCheck(self, node, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- dx = ox - node.x
- dy = oy - node.y
- d = math.sqrt(dx * dx + dy * dy)
- if d <= size:
- return False # collision
-
- return True # safe
-
-
-class Node():
- """
- RRT Node
- """
-
- def __init__(self, x, y):
- self.x = x
- self.y = y
- self.parent = None
-
-
-def main(gx=5.0, gy=10.0):
- print("start " + __file__)
-
- # ====Search Path with RRT====
- obstacleList = [
- (5, 5, 1),
- (3, 6, 2),
- (3, 8, 2),
- (3, 10, 2),
- (7, 5, 2),
- (9, 5, 2)
- ] # [x,y,size]
- # Set Initial parameters
- rrt = RRT(start=[0, 0], goal=[gx, gy],
- randArea=[-2, 15], obstacleList=obstacleList)
- path = rrt.Planning(animation=show_animation)
-
- # Draw final path
- if show_animation: # pragma: no cover
- rrt.DrawGraph()
- plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
- plt.grid(True)
- plt.show()
-
-
-if __name__ == '__main__':
- main()
diff --git a/PathPlanning/RRT/sobol/__init__.py b/PathPlanning/RRT/sobol/__init__.py
new file mode 100644
index 0000000000..c95ac8983b
--- /dev/null
+++ b/PathPlanning/RRT/sobol/__init__.py
@@ -0,0 +1 @@
+from .sobol import i4_sobol as sobol_quasirand
diff --git a/PathPlanning/RRT/sobol/sobol.py b/PathPlanning/RRT/sobol/sobol.py
new file mode 100644
index 0000000000..520d686a1d
--- /dev/null
+++ b/PathPlanning/RRT/sobol/sobol.py
@@ -0,0 +1,911 @@
+"""
+ Licensing:
+ This code is distributed under the MIT license.
+
+ Authors:
+ Original FORTRAN77 version of i4_sobol by Bennett Fox.
+ MATLAB version by John Burkardt.
+ PYTHON version by Corrado Chisari
+
+ Original Python version of is_prime by Corrado Chisari
+
+ Original MATLAB versions of other functions by John Burkardt.
+ PYTHON versions by Corrado Chisari
+
+ Original code is available at
+ https://people.sc.fsu.edu/~jburkardt/py_src/sobol/sobol.html
+
+ Note: the i4 prefix means that the function takes a numeric argument or
+ returns a number which is interpreted inside the function as a 4
+ byte integer
+ Note: the r4 prefix means that the function takes a numeric argument or
+ returns a number which is interpreted inside the function as a 4
+ byte float
+"""
+import math
+import sys
+import numpy as np
+
+atmost = None
+dim_max = None
+dim_num_save = None
+initialized = None
+lastq = None
+log_max = None
+maxcol = None
+poly = None
+recipd = None
+seed_save = None
+v = None
+
+
+def i4_bit_hi1(n):
+ """
+ I4_BIT_HI1 returns the position of the high 1 bit base 2 in an I4.
+
+ Discussion:
+
+ An I4 is an integer ( kind = 4 ) value.
+
+ Example:
+
+ N Binary Hi 1
+ ---- -------- ----
+ 0 0 0
+ 1 1 1
+ 2 10 2
+ 3 11 2
+ 4 100 3
+ 5 101 3
+ 6 110 3
+ 7 111 3
+ 8 1000 4
+ 9 1001 4
+ 10 1010 4
+ 11 1011 4
+ 12 1100 4
+ 13 1101 4
+ 14 1110 4
+ 15 1111 4
+ 16 10000 5
+ 17 10001 5
+ 1023 1111111111 10
+ 1024 10000000000 11
+ 1025 10000000001 11
+
+ Licensing:
+
+ This code is distributed under the GNU LGPL license.
+
+ Modified:
+
+ 26 October 2014
+
+ Author:
+
+ John Burkardt
+
+ Parameters:
+
+ Input, integer N, the integer to be measured.
+ N should be nonnegative. If N is nonpositive, the function
+ will always be 0.
+
+ Output, integer BIT, the position of the highest bit.
+
+ """
+ i = n
+ bit = 0
+
+ while True:
+
+ if i <= 0:
+ break
+
+ bit = bit + 1
+ i = i // 2
+
+ return bit
+
+
+def i4_bit_lo0(n):
+ """
+ I4_BIT_LO0 returns the position of the low 0 bit base 2 in an I4.
+
+ Discussion:
+
+ An I4 is an integer ( kind = 4 ) value.
+
+ Example:
+
+ N Binary Lo 0
+ ---- -------- ----
+ 0 0 1
+ 1 1 2
+ 2 10 1
+ 3 11 3
+ 4 100 1
+ 5 101 2
+ 6 110 1
+ 7 111 4
+ 8 1000 1
+ 9 1001 2
+ 10 1010 1
+ 11 1011 3
+ 12 1100 1
+ 13 1101 2
+ 14 1110 1
+ 15 1111 5
+ 16 10000 1
+ 17 10001 2
+ 1023 1111111111 11
+ 1024 10000000000 1
+ 1025 10000000001 2
+
+ Licensing:
+
+ This code is distributed under the GNU LGPL license.
+
+ Modified:
+
+ 08 February 2018
+
+ Author:
+
+ John Burkardt
+
+ Parameters:
+
+ Input, integer N, the integer to be measured.
+ N should be nonnegative.
+
+ Output, integer BIT, the position of the low 1 bit.
+
+ """
+ bit = 0
+ i = n
+
+ while True:
+
+ bit = bit + 1
+ i2 = i // 2
+
+ if i == 2 * i2:
+ break
+
+ i = i2
+
+ return bit
+
+
+def i4_sobol_generate(m, n, skip):
+ """
+
+
+ I4_SOBOL_GENERATE generates a Sobol dataset.
+
+ Licensing:
+
+ This code is distributed under the MIT license.
+
+ Modified:
+
+ 22 February 2011
+
+ Author:
+
+ Original MATLAB version by John Burkardt.
+ PYTHON version by Corrado Chisari
+
+ Parameters:
+
+ Input, integer M, the spatial dimension.
+
+ Input, integer N, the number of points to generate.
+
+ Input, integer SKIP, the number of initial points to skip.
+
+ Output, real R(M,N), the points.
+
+ """
+ r = np.zeros((m, n))
+ for j in range(1, n + 1):
+ seed = skip + j - 2
+ [r[0:m, j - 1], seed] = i4_sobol(m, seed)
+ return r
+
+
+def i4_sobol(dim_num, seed):
+ """
+
+
+ I4_SOBOL generates a new quasirandom Sobol vector with each call.
+
+ Discussion:
+
+ The routine adapts the ideas of Antonov and Saleev.
+
+ Licensing:
+
+ This code is distributed under the MIT license.
+
+ Modified:
+
+ 22 February 2011
+
+ Author:
+
+ Original FORTRAN77 version by Bennett Fox.
+ MATLAB version by John Burkardt.
+ PYTHON version by Corrado Chisari
+
+ Reference:
+
+ Antonov, Saleev,
+ USSR Computational Mathematics and Mathematical Physics,
+ olume 19, 19, pages 252 - 256.
+
+ Paul Bratley, Bennett Fox,
+ Algorithm 659:
+ Implementing Sobol's Quasirandom Sequence Generator,
+ ACM Transactions on Mathematical Software,
+ Volume 14, Number 1, pages 88-100, 1988.
+
+ Bennett Fox,
+ Algorithm 647:
+ Implementation and Relative Efficiency of Quasirandom
+ Sequence Generators,
+ ACM Transactions on Mathematical Software,
+ Volume 12, Number 4, pages 362-376, 1986.
+
+ Ilya Sobol,
+ USSR Computational Mathematics and Mathematical Physics,
+ Volume 16, pages 236-242, 1977.
+
+ Ilya Sobol, Levitan,
+ The Production of Points Uniformly Distributed in a Multidimensional
+ Cube (in Russian),
+ Preprint IPM Akad. Nauk SSSR,
+ Number 40, Moscow 1976.
+
+ Parameters:
+
+ Input, integer DIM_NUM, the number of spatial dimensions.
+ DIM_NUM must satisfy 1 <= DIM_NUM <= 40.
+
+ Input/output, integer SEED, the "seed" for the sequence.
+ This is essentially the index in the sequence of the quasirandom
+ value to be generated. On output, SEED has been set to the
+ appropriate next value, usually simply SEED+1.
+ If SEED is less than 0 on input, it is treated as though it were 0.
+ An input value of 0 requests the first (0-th) element of the sequence.
+
+ Output, real QUASI(DIM_NUM), the next quasirandom vector.
+
+ """
+
+ global atmost
+ global dim_max
+ global dim_num_save
+ global initialized
+ global lastq
+ global log_max
+ global maxcol
+ global poly
+ global recipd
+ global seed_save
+ global v
+
+ if not initialized or dim_num != dim_num_save:
+ initialized = 1
+ dim_max = 40
+ dim_num_save = -1
+ log_max = 30
+ seed_save = -1
+ #
+ # Initialize (part of) V.
+ #
+ v = np.zeros((dim_max, log_max))
+ v[0:40, 0] = np.transpose([
+ 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
+ 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1
+ ])
+
+ v[2:40, 1] = np.transpose([
+ 1, 3, 1, 3, 1, 3, 3, 1, 3, 1, 3, 1, 3, 1, 1, 3, 1, 3, 1, 3, 1, 3,
+ 3, 1, 3, 1, 3, 1, 3, 1, 1, 3, 1, 3, 1, 3, 1, 3
+ ])
+
+ v[3:40, 2] = np.transpose([
+ 7, 5, 1, 3, 3, 7, 5, 5, 7, 7, 1, 3, 3, 7, 5, 1, 1, 5, 3, 3, 1, 7,
+ 5, 1, 3, 3, 7, 5, 1, 1, 5, 7, 7, 5, 1, 3, 3
+ ])
+
+ v[5:40, 3] = np.transpose([
+ 1, 7, 9, 13, 11, 1, 3, 7, 9, 5, 13, 13, 11, 3, 15, 5, 3, 15, 7, 9,
+ 13, 9, 1, 11, 7, 5, 15, 1, 15, 11, 5, 3, 1, 7, 9
+ ])
+
+ v[7:40, 4] = np.transpose([
+ 9, 3, 27, 15, 29, 21, 23, 19, 11, 25, 7, 13, 17, 1, 25, 29, 3, 31,
+ 11, 5, 23, 27, 19, 21, 5, 1, 17, 13, 7, 15, 9, 31, 9
+ ])
+
+ v[13:40, 5] = np.transpose([
+ 37, 33, 7, 5, 11, 39, 63, 27, 17, 15, 23, 29, 3, 21, 13, 31, 25, 9,
+ 49, 33, 19, 29, 11, 19, 27, 15, 25
+ ])
+
+ v[19:40, 6] = np.transpose([
+ 13, 33, 115, 41, 79, 17, 29, 119, 75, 73, 105, 7, 59, 65, 21, 3,
+ 113, 61, 89, 45, 107
+ ])
+
+ v[37:40, 7] = np.transpose([7, 23, 39])
+ #
+ # Set POLY.
+ #
+ poly = [
+ 1, 3, 7, 11, 13, 19, 25, 37, 59, 47, 61, 55, 41, 67, 97, 91, 109,
+ 103, 115, 131, 193, 137, 145, 143, 241, 157, 185, 167, 229, 171,
+ 213, 191, 253, 203, 211, 239, 247, 285, 369, 299
+ ]
+
+ atmost = 2**log_max - 1
+ #
+ # Find the number of bits in ATMOST.
+ #
+ maxcol = i4_bit_hi1(atmost)
+ #
+ # Initialize row 1 of V.
+ #
+ v[0, 0:maxcol] = 1
+
+ # Things to do only if the dimension changed.
+
+ if dim_num != dim_num_save:
+ #
+ # Check parameters.
+ #
+ if (dim_num < 1 or dim_max < dim_num):
+ print('I4_SOBOL - Fatal error!')
+ print(' The spatial dimension DIM_NUM should satisfy:')
+ print(f' 1 <= DIM_NUM <= {dim_max:d}')
+ print(f' But this input value is DIM_NUM = {dim_num:d}')
+ return None
+
+ dim_num_save = dim_num
+ #
+ # Initialize the remaining rows of V.
+ #
+ for i in range(2, dim_num + 1):
+ #
+ # The bits of the integer POLY(I) gives the form of polynomial
+ # I.
+ #
+ # Find the degree of polynomial I from binary encoding.
+ #
+ j = poly[i - 1]
+ m = 0
+ while True:
+ j = math.floor(j / 2.)
+ if (j <= 0):
+ break
+ m = m + 1
+ #
+ # Expand this bit pattern to separate components of the logical
+ # array INCLUD.
+ #
+ j = poly[i - 1]
+ includ = np.zeros(m)
+ for k in range(m, 0, -1):
+ j2 = math.floor(j / 2.)
+ includ[k - 1] = (j != 2 * j2)
+ j = j2
+ #
+ # Calculate the remaining elements of row I as explained
+ # in Bratley and Fox, section 2.
+ #
+ for j in range(m + 1, maxcol + 1):
+ newv = v[i - 1, j - m - 1]
+ l_var = 1
+ for k in range(1, m + 1):
+ l_var = 2 * l_var
+ if (includ[k - 1]):
+ newv = np.bitwise_xor(
+ int(newv), int(l_var * v[i - 1, j - k - 1]))
+ v[i - 1, j - 1] = newv
+#
+# Multiply columns of V by appropriate power of 2.
+#
+ l_var = 1
+ for j in range(maxcol - 1, 0, -1):
+ l_var = 2 * l_var
+ v[0:dim_num, j - 1] = v[0:dim_num, j - 1] * l_var
+#
+# RECIPD is 1/(common denominator of the elements in V).
+#
+ recipd = 1.0 / (2 * l_var)
+ lastq = np.zeros(dim_num)
+
+ seed = int(math.floor(seed))
+
+ if (seed < 0):
+ seed = 0
+
+ if (seed == 0):
+ l_var = 1
+ lastq = np.zeros(dim_num)
+
+ elif (seed == seed_save + 1):
+ #
+ # Find the position of the right-hand zero in SEED.
+ #
+ l_var = i4_bit_lo0(seed)
+
+ elif seed <= seed_save:
+
+ seed_save = 0
+ lastq = np.zeros(dim_num)
+
+ for seed_temp in range(int(seed_save), int(seed)):
+ l_var = i4_bit_lo0(seed_temp)
+ for i in range(1, dim_num + 1):
+ lastq[i - 1] = np.bitwise_xor(
+ int(lastq[i - 1]), int(v[i - 1, l_var - 1]))
+
+ l_var = i4_bit_lo0(seed)
+
+ elif (seed_save + 1 < seed):
+
+ for seed_temp in range(int(seed_save + 1), int(seed)):
+ l_var = i4_bit_lo0(seed_temp)
+ for i in range(1, dim_num + 1):
+ lastq[i - 1] = np.bitwise_xor(
+ int(lastq[i - 1]), int(v[i - 1, l_var - 1]))
+
+ l_var = i4_bit_lo0(seed)
+#
+# Check that the user is not calling too many times!
+#
+ if maxcol < l_var:
+ print('I4_SOBOL - Fatal error!')
+ print(' Too many calls!')
+ print(f' MAXCOL = {maxcol:d}\n')
+ print(f' L = {l_var:d}\n')
+ return None
+
+
+#
+# Calculate the new components of QUASI.
+#
+ quasi = np.zeros(dim_num)
+ for i in range(1, dim_num + 1):
+ quasi[i - 1] = lastq[i - 1] * recipd
+ lastq[i - 1] = np.bitwise_xor(
+ int(lastq[i - 1]), int(v[i - 1, l_var - 1]))
+
+ seed_save = seed
+ seed = seed + 1
+
+ return [quasi, seed]
+
+
+def i4_uniform_ab(a, b, seed):
+ """
+
+
+ I4_UNIFORM_AB returns a scaled pseudorandom I4.
+
+ Discussion:
+
+ The pseudorandom number will be scaled to be uniformly distributed
+ between A and B.
+
+ Licensing:
+
+ This code is distributed under the GNU LGPL license.
+
+ Modified:
+
+ 05 April 2013
+
+ Author:
+
+ John Burkardt
+
+ Reference:
+
+ Paul Bratley, Bennett Fox, Linus Schrage,
+ A Guide to Simulation,
+ Second Edition,
+ Springer, 1987,
+ ISBN: 0387964673,
+ LC: QA76.9.C65.B73.
+
+ Bennett Fox,
+ Algorithm 647:
+ Implementation and Relative Efficiency of Quasirandom
+ Sequence Generators,
+ ACM Transactions on Mathematical Software,
+ Volume 12, Number 4, December 1986, pages 362-376.
+
+ Pierre L'Ecuyer,
+ Random Number Generation,
+ in Handbook of Simulation,
+ edited by Jerry Banks,
+ Wiley, 1998,
+ ISBN: 0471134031,
+ LC: T57.62.H37.
+
+ Peter Lewis, Allen Goodman, James Miller,
+ A Pseudo-Random Number Generator for the System/360,
+ IBM Systems Journal,
+ Volume 8, Number 2, 1969, pages 136-143.
+
+ Parameters:
+
+ Input, integer A, B, the minimum and maximum acceptable values.
+
+ Input, integer SEED, a seed for the random number generator.
+
+ Output, integer C, the randomly chosen integer.
+
+ Output, integer SEED, the updated seed.
+
+ """
+
+ i4_huge = 2147483647
+
+ seed = int(seed)
+
+ seed = (seed % i4_huge)
+
+ if seed < 0:
+ seed = seed + i4_huge
+
+ if seed == 0:
+ print('')
+ print('I4_UNIFORM_AB - Fatal error!')
+ print(' Input SEED = 0!')
+ sys.exit('I4_UNIFORM_AB - Fatal error!')
+
+ k = (seed // 127773)
+
+ seed = 167 * (seed - k * 127773) - k * 2836
+
+ if seed < 0:
+ seed = seed + i4_huge
+
+ r = seed * 4.656612875E-10
+ #
+ # Scale R to lie between A-0.5 and B+0.5.
+ #
+ a = round(a)
+ b = round(b)
+
+ r = (1.0 - r) * (min(a, b) - 0.5) \
+ + r * (max(a, b) + 0.5)
+ #
+ # Use rounding to convert R to an integer between A and B.
+ #
+ value = round(r)
+
+ value = max(value, min(a, b))
+ value = min(value, max(a, b))
+ value = int(value)
+
+ return value, seed
+
+
+def prime_ge(n):
+ """
+
+
+ PRIME_GE returns the smallest prime greater than or equal to N.
+
+ Example:
+
+ N PRIME_GE
+
+ -10 2
+ 1 2
+ 2 2
+ 3 3
+ 4 5
+ 5 5
+ 6 7
+ 7 7
+ 8 11
+ 9 11
+ 10 11
+
+ Licensing:
+
+ This code is distributed under the MIT license.
+
+ Modified:
+
+ 22 February 2011
+
+ Author:
+
+ Original MATLAB version by John Burkardt.
+ PYTHON version by Corrado Chisari
+
+ Parameters:
+
+ Input, integer N, the number to be bounded.
+
+ Output, integer P, the smallest prime number that is greater
+ than or equal to N.
+
+ """
+ p = max(math.ceil(n), 2)
+ while not isprime(p):
+ p = p + 1
+
+ return p
+
+
+def isprime(n):
+ """
+
+
+ IS_PRIME returns True if N is a prime number, False otherwise
+
+ Licensing:
+
+ This code is distributed under the MIT license.
+
+ Modified:
+
+ 22 February 2011
+
+ Author:
+
+ Corrado Chisari
+
+ Parameters:
+
+ Input, integer N, the number to be checked.
+
+ Output, boolean value, True or False
+
+ """
+ if n != int(n) or n < 1:
+ return False
+ p = 2
+ while p < n:
+ if n % p == 0:
+ return False
+ p += 1
+
+ return True
+
+
+def r4_uniform_01(seed):
+ """
+
+
+ R4_UNIFORM_01 returns a unit pseudorandom R4.
+
+ Discussion:
+
+ This routine implements the recursion
+
+ seed = 167 * seed mod ( 2^31 - 1 )
+ r = seed / ( 2^31 - 1 )
+
+ The integer arithmetic never requires more than 32 bits,
+ including a sign bit.
+
+ If the initial seed is 12345, then the first three computations are
+
+ Input Output R4_UNIFORM_01
+ SEED SEED
+
+ 12345 207482415 0.096616
+ 207482415 1790989824 0.833995
+ 1790989824 2035175616 0.947702
+
+ Licensing:
+
+ This code is distributed under the GNU LGPL license.
+
+ Modified:
+
+ 04 April 2013
+
+ Author:
+
+ John Burkardt
+
+ Reference:
+
+ Paul Bratley, Bennett Fox, Linus Schrage,
+ A Guide to Simulation,
+ Second Edition,
+ Springer, 1987,
+ ISBN: 0387964673,
+ LC: QA76.9.C65.B73.
+
+ Bennett Fox,
+ Algorithm 647:
+ Implementation and Relative Efficiency of Quasirandom
+ Sequence Generators,
+ ACM Transactions on Mathematical Software,
+ Volume 12, Number 4, December 1986, pages 362-376.
+
+ Pierre L'Ecuyer,
+ Random Number Generation,
+ in Handbook of Simulation,
+ edited by Jerry Banks,
+ Wiley, 1998,
+ ISBN: 0471134031,
+ LC: T57.62.H37.
+
+ Peter Lewis, Allen Goodman, James Miller,
+ A Pseudo-Random Number Generator for the System/360,
+ IBM Systems Journal,
+ Volume 8, Number 2, 1969, pages 136-143.
+
+ Parameters:
+
+ Input, integer SEED, the integer "seed" used to generate
+ the output random number. SEED should not be 0.
+
+ Output, real R, a random value between 0 and 1.
+
+ Output, integer SEED, the updated seed. This would
+ normally be used as the input seed on the next call.
+
+ """
+
+ i4_huge = 2147483647
+
+ if (seed == 0):
+ print('')
+ print('R4_UNIFORM_01 - Fatal error!')
+ print(' Input SEED = 0!')
+ sys.exit('R4_UNIFORM_01 - Fatal error!')
+
+ seed = (seed % i4_huge)
+
+ if seed < 0:
+ seed = seed + i4_huge
+
+ k = (seed // 127773)
+
+ seed = 167 * (seed - k * 127773) - k * 2836
+
+ if seed < 0:
+ seed = seed + i4_huge
+
+ r = seed * 4.656612875E-10
+
+ return r, seed
+
+
+def r8mat_write(filename, m, n, a):
+ """
+
+
+ R8MAT_WRITE writes an R8MAT to a file.
+
+ Licensing:
+
+ This code is distributed under the GNU LGPL license.
+
+ Modified:
+
+ 12 October 2014
+
+ Author:
+
+ John Burkardt
+
+ Parameters:
+
+ Input, string FILENAME, the name of the output file.
+
+ Input, integer M, the number of rows in A.
+
+ Input, integer N, the number of columns in A.
+
+ Input, real A(M,N), the matrix.
+ """
+
+ with open(filename, 'w') as output:
+ for i in range(0, m):
+ for j in range(0, n):
+ s = f' {a[i, j]:g}'
+ output.write(s)
+ output.write('\n')
+
+
+def tau_sobol(dim_num):
+ """
+
+
+ TAU_SOBOL defines favorable starting seeds for Sobol sequences.
+
+ Discussion:
+
+ For spatial dimensions 1 through 13, this routine returns
+ a "favorable" value TAU by which an appropriate starting point
+ in the Sobol sequence can be determined.
+
+ These starting points have the form N = 2**K, where
+ for integration problems, it is desirable that
+ TAU + DIM_NUM - 1 <= K
+ while for optimization problems, it is desirable that
+ TAU < K.
+
+ Licensing:
+
+ This code is distributed under the MIT license.
+
+ Modified:
+
+ 22 February 2011
+
+ Author:
+
+ Original FORTRAN77 version by Bennett Fox.
+ MATLAB version by John Burkardt.
+ PYTHON version by Corrado Chisari
+
+ Reference:
+
+ IA Antonov, VM Saleev,
+ USSR Computational Mathematics and Mathematical Physics,
+ Volume 19, 19, pages 252 - 256.
+
+ Paul Bratley, Bennett Fox,
+ Algorithm 659:
+ Implementing Sobol's Quasirandom Sequence Generator,
+ ACM Transactions on Mathematical Software,
+ Volume 14, Number 1, pages 88-100, 1988.
+
+ Bennett Fox,
+ Algorithm 647:
+ Implementation and Relative Efficiency of Quasirandom
+ Sequence Generators,
+ ACM Transactions on Mathematical Software,
+ Volume 12, Number 4, pages 362-376, 1986.
+
+ Stephen Joe, Frances Kuo
+ Remark on Algorithm 659:
+ Implementing Sobol's Quasirandom Sequence Generator,
+ ACM Transactions on Mathematical Software,
+ Volume 29, Number 1, pages 49-57, March 2003.
+
+ Ilya Sobol,
+ USSR Computational Mathematics and Mathematical Physics,
+ Volume 16, pages 236-242, 1977.
+
+ Ilya Sobol, YL Levitan,
+ The Production of Points Uniformly Distributed in a Multidimensional
+ Cube (in Russian),
+ Preprint IPM Akad. Nauk SSSR,
+ Number 40, Moscow 1976.
+
+ Parameters:
+
+ Input, integer DIM_NUM, the spatial dimension. Only values
+ of 1 through 13 will result in useful responses.
+
+ Output, integer TAU, the value TAU.
+
+ """
+ dim_max = 13
+
+ tau_table = [0, 0, 1, 3, 5, 8, 11, 15, 19, 23, 27, 31, 35]
+
+ if 1 <= dim_num <= dim_max:
+ tau = tau_table[dim_num]
+ else:
+ tau = -1
+
+ return tau
diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py
index 54752ef81e..f938419f35 100644
--- a/PathPlanning/RRTDubins/rrt_dubins.py
+++ b/PathPlanning/RRTDubins/rrt_dubins.py
@@ -1,206 +1,212 @@
"""
-Path Planning Sample Code with RRT for car like robot.
+Path planning Sample Code with RRT with Dubins path
author: AtsushiSakai(@Atsushi_twi)
"""
-import matplotlib.pyplot as plt
-import numpy as np
import copy
import math
import random
+import numpy as np
+import matplotlib.pyplot as plt
import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../DubinsPath/")
-
-try:
- import dubins_path_planning
-except:
- raise
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) # root dir
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+from RRT.rrt import RRT
+from DubinsPath import dubins_path_planner
+from utils.plot import plot_arrow
show_animation = True
-class RRT():
+class RRTDubins(RRT):
"""
- Class for RRT Planning
+ Class for RRT planning with Dubins path
"""
- def __init__(self, start, goal, obstacleList, randArea,
- goalSampleRate=10, maxIter=1000):
+ class Node(RRT.Node):
+ """
+ RRT Node
+ """
+
+ def __init__(self, x, y, yaw):
+ super().__init__(x, y)
+ self.cost = 0
+ self.yaw = yaw
+ self.path_yaw = []
+
+ def __init__(self, start, goal, obstacle_list, rand_area,
+ goal_sample_rate=10,
+ max_iter=200,
+ robot_radius=0.0
+ ):
"""
Setting Parameter
start:Start Position [x,y]
goal:Goal Position [x,y]
obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
+ randArea:Random Sampling Area [min,max]
+ robot_radius: robot body modeled as circle with given radius
"""
- self.start = Node(start[0], start[1], start[2])
- self.end = Node(goal[0], goal[1], goal[2])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=False):
+ self.start = self.Node(start[0], start[1], start[2])
+ self.end = self.Node(goal[0], goal[1], goal[2])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+
+ self.curvature = 1.0 # for dubins path
+ self.goal_yaw_th = np.deg2rad(1.0)
+ self.goal_xy_th = 0.5
+ self.robot_radius = robot_radius
+
+ def planning(self, animation=True, search_until_max_iter=True):
"""
- Pathplanning
+ execute planning
animation: flag for animation on or off
"""
- self.nodeList = [self.start]
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.GetNearestListIndex(self.nodeList, rnd)
-
- newNode = self.steer(rnd, nind)
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind], rnd)
- if self.__CollisionCheck(newNode, self.obstacleList):
- self.nodeList.append(newNode)
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ self.node_list.append(new_node)
if animation and i % 5 == 0:
- self.DrawGraph(rnd=rnd)
+ self.plot_start_goal_arrow()
+ self.draw_graph(rnd)
- # generate coruse
- lastIndex = self.get_best_last_index()
- # print(lastIndex)
+ if (not search_until_max_iter) and new_node: # check reaching the goal
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
- if lastIndex is None:
- return None
+ print("reached max iteration")
- path = self.gen_final_course(lastIndex)
- return path
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
+ else:
+ print("Cannot find path")
- def pi_2_pi(self, angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return None
- def steer(self, rnd, nind):
- # print(rnd)
- curvature = 1.0
+ def draw_graph(self, rnd=None): # pragma: no cover
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
- nearestNode = self.nodeList[nind]
+ for (ox, oy, size) in self.obstacle_list:
+ plt.plot(ox, oy, "ok", ms=30 * size)
- px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning(
- nearestNode.x, nearestNode.y, nearestNode.yaw, rnd[0], rnd[1], rnd[2], curvature)
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis([-2, 15, -2, 15])
+ plt.grid(True)
+ self.plot_start_goal_arrow()
+ plt.pause(0.01)
- newNode = copy.deepcopy(nearestNode)
- newNode.x = px[-1]
- newNode.y = py[-1]
- newNode.yaw = pyaw[-1]
+ def plot_start_goal_arrow(self): # pragma: no cover
+ plot_arrow(self.start.x, self.start.y, self.start.yaw)
+ plot_arrow(self.end.x, self.end.y, self.end.yaw)
- newNode.path_x = px
- newNode.path_y = py
- newNode.path_yaw = pyaw
- newNode.cost += clen
- newNode.parent = nind
+ def steer(self, from_node, to_node):
- return newNode
+ px, py, pyaw, mode, course_lengths = \
+ dubins_path_planner.plan_dubins_path(
+ from_node.x, from_node.y, from_node.yaw,
+ to_node.x, to_node.y, to_node.yaw, self.curvature)
- def get_random_point(self):
+ if len(px) <= 1: # cannot find a dubins path
+ return None
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand),
- random.uniform(-math.pi, math.pi)
- ]
- else: # goal point sampling
- rnd = [self.end.x, self.end.y, self.end.yaw]
+ new_node = copy.deepcopy(from_node)
+ new_node.x = px[-1]
+ new_node.y = py[-1]
+ new_node.yaw = pyaw[-1]
- return rnd
+ new_node.path_x = px
+ new_node.path_y = py
+ new_node.path_yaw = pyaw
+ new_node.cost += sum([abs(c) for c in course_lengths])
+ new_node.parent = from_node
- def get_best_last_index(self):
- # print("get_best_last_index")
+ return new_node
- disglist = [self.calc_dist_to_goal(
- node.x, node.y) for node in self.nodeList]
- goalinds = [disglist.index(i) for i in disglist if i <= 0.1]
- # print(goalinds)
+ def calc_new_cost(self, from_node, to_node):
- mincost = min([self.nodeList[i].cost for i in goalinds])
- for i in goalinds:
- if self.nodeList[i].cost == mincost:
- return i
+ _, _, _, _, course_length = dubins_path_planner.plan_dubins_path(
+ from_node.x, from_node.y, from_node.yaw,
+ to_node.x, to_node.y, to_node.yaw, self.curvature)
- return None
+ return from_node.cost + course_length
- def gen_final_course(self, goalind):
- path = [[self.end.x, self.end.y]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
- for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
- path.append([ix, iy])
- # path.append([node.x, node.y])
- goalind = node.parent
- path.append([self.start.x, self.start.y])
- return path
-
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def DrawGraph(self, rnd=None): # pragma: no cover
- plt.clf()
- if rnd is not None:
- plt.plot(rnd[0], rnd[1], "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot(node.path_x, node.path_y, "-g")
+ def get_random_node(self):
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- dubins_path_planning.plot_arrow(
- self.start.x, self.start.y, self.start.yaw)
- dubins_path_planning.plot_arrow(
- self.end.x, self.end.y, self.end.yaw)
-
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = self.Node(random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand),
+ random.uniform(-math.pi, math.pi)
+ )
+ else: # goal point sampling
+ rnd = self.Node(self.end.x, self.end.y, self.end.yaw)
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd[0]) ** 2
- + (node.y - rnd[1]) ** 2
- + (node.yaw - rnd[2] ** 2) for node in nodeList]
- minind = dlist.index(min(dlist))
+ return rnd
- return minind
+ def search_best_goal_node(self):
- def __CollisionCheck(self, node, obstacleList):
+ goal_indexes = []
+ for (i, node) in enumerate(self.node_list):
+ if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th:
+ goal_indexes.append(i)
- for (ox, oy, size) in obstacleList:
- for (ix, iy) in zip(node.path_x, node.path_y):
- dx = ox - ix
- dy = oy - iy
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
+ # angle check
+ final_goal_indexes = []
+ for i in goal_indexes:
+ if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th:
+ final_goal_indexes.append(i)
- return True # safe
+ if not final_goal_indexes:
+ return None
+ min_cost = min([self.node_list[i].cost for i in final_goal_indexes])
+ for i in final_goal_indexes:
+ if self.node_list[i].cost == min_cost:
+ return i
-class Node():
- """
- RRT Node
- """
+ return None
- def __init__(self, x, y, yaw):
- self.x = x
- self.y = y
- self.yaw = yaw
- self.path_x = []
- self.path_y = []
- self.path_yaw = []
- self.cost = 0.0
- self.parent = None
+ def generate_final_course(self, goal_index):
+ print("final")
+ path = [[self.end.x, self.end.y]]
+ node = self.node_list[goal_index]
+ while node.parent:
+ for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
+ path.append([ix, iy])
+ node = node.parent
+ path.append([self.start.x, self.start.y])
+ return path
def main():
+
print("Start " + __file__)
# ====Search Path with RRT====
obstacleList = [
@@ -216,12 +222,12 @@ def main():
start = [0.0, 0.0, np.deg2rad(0.0)]
goal = [10.0, 10.0, np.deg2rad(0.0)]
- rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList)
- path = rrt.Planning(animation=show_animation)
+ rrt_dubins = RRTDubins(start, goal, obstacleList, [-2.0, 15.0])
+ path = rrt_dubins.planning(animation=show_animation)
# Draw final path
if show_animation: # pragma: no cover
- rrt.DrawGraph()
+ rrt_dubins.draw_graph()
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
plt.grid(True)
plt.pause(0.001)
diff --git a/PathPlanning/RRTStar/__init__.py b/PathPlanning/RRTStar/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py
new file mode 100644
index 0000000000..dcb1a066eb
--- /dev/null
+++ b/PathPlanning/RRTStar/rrt_star.py
@@ -0,0 +1,289 @@
+"""
+
+Path planning Sample Code with RRT*
+
+author: Atsushi Sakai(@Atsushi_twi)
+
+"""
+
+import math
+import sys
+import matplotlib.pyplot as plt
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+
+from RRT.rrt import RRT
+
+show_animation = True
+
+
+class RRTStar(RRT):
+ """
+ Class for RRT Star planning
+ """
+
+ class Node(RRT.Node):
+ def __init__(self, x, y):
+ super().__init__(x, y)
+ self.cost = 0.0
+
+ def __init__(self,
+ start,
+ goal,
+ obstacle_list,
+ rand_area,
+ expand_dis=30.0,
+ path_resolution=1.0,
+ goal_sample_rate=20,
+ max_iter=300,
+ connect_circle_dist=50.0,
+ search_until_max_iter=False,
+ robot_radius=0.0):
+ """
+ Setting Parameter
+
+ start:Start Position [x,y]
+ goal:Goal Position [x,y]
+ obstacleList:obstacle Positions [[x,y,size],...]
+ randArea:Random Sampling Area [min,max]
+
+ """
+ super().__init__(start, goal, obstacle_list, rand_area, expand_dis,
+ path_resolution, goal_sample_rate, max_iter,
+ robot_radius=robot_radius)
+ self.connect_circle_dist = connect_circle_dist
+ self.goal_node = self.Node(goal[0], goal[1])
+ self.search_until_max_iter = search_until_max_iter
+ self.node_list = []
+
+ def planning(self, animation=True):
+ """
+ rrt star path planning
+
+ animation: flag for animation on or off .
+ """
+
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind], rnd,
+ self.expand_dis)
+ near_node = self.node_list[nearest_ind]
+ new_node.cost = near_node.cost + \
+ math.hypot(new_node.x-near_node.x,
+ new_node.y-near_node.y)
+
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ near_inds = self.find_near_nodes(new_node)
+ node_with_updated_parent = self.choose_parent(
+ new_node, near_inds)
+ if node_with_updated_parent:
+ self.rewire(node_with_updated_parent, near_inds)
+ self.node_list.append(node_with_updated_parent)
+ else:
+ self.node_list.append(new_node)
+
+ if animation:
+ self.draw_graph(rnd)
+
+ if ((not self.search_until_max_iter)
+ and new_node): # if reaches goal
+ last_index = self.search_best_goal_node()
+ if last_index is not None:
+ return self.generate_final_course(last_index)
+
+ print("reached max iteration")
+
+ last_index = self.search_best_goal_node()
+ if last_index is not None:
+ return self.generate_final_course(last_index)
+
+ return None
+
+ def choose_parent(self, new_node, near_inds):
+ """
+ Computes the cheapest point to new_node contained in the list
+ near_inds and set such a node as the parent of new_node.
+ Arguments:
+ --------
+ new_node, Node
+ randomly generated node with a path from its neared point
+ There are not coalitions between this node and th tree.
+ near_inds: list
+ Indices of indices of the nodes what are near to new_node
+
+ Returns.
+ ------
+ Node, a copy of new_node
+ """
+ if not near_inds:
+ return None
+
+ # search nearest cost in near_inds
+ costs = []
+ for i in near_inds:
+ near_node = self.node_list[i]
+ t_node = self.steer(near_node, new_node)
+ if t_node and self.check_collision(
+ t_node, self.obstacle_list, self.robot_radius):
+ costs.append(self.calc_new_cost(near_node, new_node))
+ else:
+ costs.append(float("inf")) # the cost of collision node
+ min_cost = min(costs)
+
+ if min_cost == float("inf"):
+ print("There is no good path.(min_cost is inf)")
+ return None
+
+ min_ind = near_inds[costs.index(min_cost)]
+ new_node = self.steer(self.node_list[min_ind], new_node)
+ new_node.cost = min_cost
+
+ return new_node
+
+ def search_best_goal_node(self):
+ dist_to_goal_list = [
+ self.calc_dist_to_goal(n.x, n.y) for n in self.node_list
+ ]
+ goal_inds = [
+ dist_to_goal_list.index(i) for i in dist_to_goal_list
+ if i <= self.expand_dis
+ ]
+
+ safe_goal_inds = []
+ for goal_ind in goal_inds:
+ t_node = self.steer(self.node_list[goal_ind], self.goal_node)
+ if self.check_collision(
+ t_node, self.obstacle_list, self.robot_radius):
+ safe_goal_inds.append(goal_ind)
+
+ if not safe_goal_inds:
+ return None
+
+ safe_goal_costs = [self.node_list[i].cost +
+ self.calc_dist_to_goal(self.node_list[i].x, self.node_list[i].y)
+ for i in safe_goal_inds]
+
+ min_cost = min(safe_goal_costs)
+ for i, cost in zip(safe_goal_inds, safe_goal_costs):
+ if cost == min_cost:
+ return i
+
+ return None
+
+ def find_near_nodes(self, new_node):
+ """
+ 1) defines a ball centered on new_node
+ 2) Returns all nodes of the three that are inside this ball
+ Arguments:
+ ---------
+ new_node: Node
+ new randomly generated node, without collisions between
+ its nearest node
+ Returns:
+ -------
+ list
+ List with the indices of the nodes inside the ball of
+ radius r
+ """
+ nnode = len(self.node_list) + 1
+ r = self.connect_circle_dist * math.sqrt(math.log(nnode) / nnode)
+ # if expand_dist exists, search vertices in a range no more than
+ # expand_dist
+ if hasattr(self, 'expand_dis'):
+ r = min(r, self.expand_dis)
+ dist_list = [(node.x - new_node.x)**2 + (node.y - new_node.y)**2
+ for node in self.node_list]
+ near_inds = [dist_list.index(i) for i in dist_list if i <= r**2]
+ return near_inds
+
+ def rewire(self, new_node, near_inds):
+ """
+ For each node in near_inds, this will check if it is cheaper to
+ arrive to them from new_node.
+ In such a case, this will re-assign the parent of the nodes in
+ near_inds to new_node.
+ Parameters:
+ ----------
+ new_node, Node
+ Node randomly added which can be joined to the tree
+
+ near_inds, list of uints
+ A list of indices of the self.new_node which contains
+ nodes within a circle of a given radius.
+ Remark: parent is designated in choose_parent.
+
+ """
+ for i in near_inds:
+ near_node = self.node_list[i]
+ edge_node = self.steer(new_node, near_node)
+ if not edge_node:
+ continue
+ edge_node.cost = self.calc_new_cost(new_node, near_node)
+
+ no_collision = self.check_collision(
+ edge_node, self.obstacle_list, self.robot_radius)
+ improved_cost = near_node.cost > edge_node.cost
+
+ if no_collision and improved_cost:
+ for node in self.node_list:
+ if node.parent == self.node_list[i]:
+ node.parent = edge_node
+ self.node_list[i] = edge_node
+ self.propagate_cost_to_leaves(self.node_list[i])
+
+ def calc_new_cost(self, from_node, to_node):
+ d, _ = self.calc_distance_and_angle(from_node, to_node)
+ return from_node.cost + d
+
+ def propagate_cost_to_leaves(self, parent_node):
+
+ for node in self.node_list:
+ if node.parent == parent_node:
+ node.cost = self.calc_new_cost(parent_node, node)
+ self.propagate_cost_to_leaves(node)
+
+
+def main():
+ print("Start " + __file__)
+
+ # ====Search Path with RRT====
+ obstacle_list = [
+ (5, 5, 1),
+ (3, 6, 2),
+ (3, 8, 2),
+ (3, 10, 2),
+ (7, 5, 2),
+ (9, 5, 2),
+ (8, 10, 1),
+ (6, 12, 1),
+ ] # [x,y,size(radius)]
+
+ # Set Initial parameters
+ rrt_star = RRTStar(
+ start=[0, 0],
+ goal=[6, 10],
+ rand_area=[-2, 15],
+ obstacle_list=obstacle_list,
+ expand_dis=1,
+ robot_radius=0.8)
+ path = rrt_star.planning(animation=show_animation)
+
+ if path is None:
+ print("Cannot find path")
+ else:
+ print("found path!!")
+
+ # Draw final path
+ if show_animation:
+ rrt_star.draw_graph()
+ plt.plot([x for (x, y) in path], [y for (x, y) in path], 'r--')
+ plt.grid(True)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/RRTStarDubins/dubins_path_planning.py b/PathPlanning/RRTStarDubins/dubins_path_planning.py
deleted file mode 100644
index b29465209b..0000000000
--- a/PathPlanning/RRTStarDubins/dubins_path_planning.py
+++ /dev/null
@@ -1,303 +0,0 @@
-"""
-
-Dubins path planner sample code
-
-author Atsushi Sakai (@Atsushi_twi)
-
-"""
-import math
-import matplotlib.pyplot as plt
-import numpy as np
-
-
-def mod2pi(theta):
- return theta - 2.0 * math.pi * math.floor(theta / 2.0 / math.pi)
-
-
-def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
-
-
-def LSL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- tmp0 = d + sa - sb
-
- mode = ["L", "S", "L"]
- p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sa - sb))
- if p_squared < 0:
- return None, None, None, mode
- tmp1 = math.atan2((cb - ca), tmp0)
- t = mod2pi(-alpha + tmp1)
- p = math.sqrt(p_squared)
- q = mod2pi(beta - tmp1)
- # print(np.rad2deg(t), p, np.rad2deg(q))
-
- return t, p, q, mode
-
-
-def RSR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- tmp0 = d - sa + sb
- mode = ["R", "S", "R"]
- p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sb - sa))
- if p_squared < 0:
- return None, None, None, mode
- tmp1 = math.atan2((ca - cb), tmp0)
- t = mod2pi(alpha - tmp1)
- p = math.sqrt(p_squared)
- q = mod2pi(-beta + tmp1)
-
- return t, p, q, mode
-
-
-def LSR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- p_squared = -2 + (d * d) + (2 * c_ab) + (2 * d * (sa + sb))
- mode = ["L", "S", "R"]
- if p_squared < 0:
- return None, None, None, mode
- p = math.sqrt(p_squared)
- tmp2 = math.atan2((-ca - cb), (d + sa + sb)) - math.atan2(-2.0, p)
- t = mod2pi(-alpha + tmp2)
- q = mod2pi(-mod2pi(beta) + tmp2)
-
- return t, p, q, mode
-
-
-def RSL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- p_squared = (d * d) - 2 + (2 * c_ab) - (2 * d * (sa + sb))
- mode = ["R", "S", "L"]
- if p_squared < 0:
- return None, None, None, mode
- p = math.sqrt(p_squared)
- tmp2 = math.atan2((ca + cb), (d - sa - sb)) - math.atan2(2.0, p)
- t = mod2pi(alpha - tmp2)
- q = mod2pi(beta - tmp2)
-
- return t, p, q, mode
-
-
-def RLR(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- mode = ["R", "L", "R"]
- tmp_rlr = (6.0 - d * d + 2.0 * c_ab + 2.0 * d * (sa - sb)) / 8.0
- if abs(tmp_rlr) > 1.0:
- return None, None, None, mode
-
- p = mod2pi(2 * math.pi - math.acos(tmp_rlr))
- t = mod2pi(alpha - math.atan2(ca - cb, d - sa + sb) + mod2pi(p / 2.0))
- q = mod2pi(alpha - beta - t + mod2pi(p))
- return t, p, q, mode
-
-
-def LRL(alpha, beta, d):
- sa = math.sin(alpha)
- sb = math.sin(beta)
- ca = math.cos(alpha)
- cb = math.cos(beta)
- c_ab = math.cos(alpha - beta)
-
- mode = ["L", "R", "L"]
- tmp_lrl = (6. - d * d + 2 * c_ab + 2 * d * (- sa + sb)) / 8.
- if abs(tmp_lrl) > 1:
- return None, None, None, mode
- p = mod2pi(2 * math.pi - math.acos(tmp_lrl))
- t = mod2pi(-alpha - math.atan2(ca - cb, d + sa - sb) + p / 2.)
- q = mod2pi(mod2pi(beta) - alpha - t + mod2pi(p))
-
- return t, p, q, mode
-
-
-def dubins_path_planning_from_origin(ex, ey, eyaw, c):
- # nomalize
- dx = ex
- dy = ey
- D = math.sqrt(dx ** 2.0 + dy ** 2.0)
- d = D / c
- # print(dx, dy, D, d)
-
- theta = mod2pi(math.atan2(dy, dx))
- alpha = mod2pi(- theta)
- beta = mod2pi(eyaw - theta)
- # print(theta, alpha, beta, d)
-
- planners = [LSL, RSR, LSR, RSL, RLR, LRL]
-
- bcost = float("inf")
- bt, bp, bq, bmode = None, None, None, None
-
- for planner in planners:
- t, p, q, mode = planner(alpha, beta, d)
- if t is None:
- # print("".join(mode) + " cannot generate path")
- continue
-
- cost = (abs(t) + abs(p) + abs(q))
- if bcost > cost:
- bt, bp, bq, bmode = t, p, q, mode
- bcost = cost
-
- # print(bmode)
- px, py, pyaw = generate_course([bt, bp, bq], bmode, c)
-
- return px, py, pyaw, bmode, bcost
-
-
-def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c):
- """
- Dubins path plannner
-
- input:
- sx x position of start point [m]
- sy y position of start point [m]
- syaw yaw angle of start point [rad]
- ex x position of end point [m]
- ey y position of end point [m]
- eyaw yaw angle of end point [rad]
- c curvature [1/m]
-
- output:
- px
- py
- pyaw
- mode
-
- """
-
- ex = ex - sx
- ey = ey - sy
-
- lex = math.cos(syaw) * ex + math.sin(syaw) * ey
- ley = - math.sin(syaw) * ex + math.cos(syaw) * ey
- leyaw = eyaw - syaw
-
- lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin(
- lex, ley, leyaw, c)
-
- px = [math.cos(-syaw) * x + math.sin(-syaw)
- * y + sx for x, y in zip(lpx, lpy)]
- py = [- math.sin(-syaw) * x + math.cos(-syaw)
- * y + sy for x, y in zip(lpx, lpy)]
- pyaw = [pi_2_pi(iyaw + syaw) for iyaw in lpyaw]
- # print(syaw)
- # pyaw = lpyaw
-
- # plt.plot(pyaw, "-r")
- # plt.plot(lpyaw, "-b")
- # plt.plot(eyaw, "*r")
- # plt.plot(syaw, "*b")
- # plt.show()
-
- return px, py, pyaw, mode, clen
-
-
-def generate_course(length, mode, c):
-
- px = [0.0]
- py = [0.0]
- pyaw = [0.0]
-
- for m, l in zip(mode, length):
- pd = 0.0
- if m == "S":
- d = 1.0 / c
- else: # turning couse
- d = np.deg2rad(3.0)
-
- while pd < abs(l - d):
- # print(pd, l)
- px.append(px[-1] + d * c * math.cos(pyaw[-1]))
- py.append(py[-1] + d * c * math.sin(pyaw[-1]))
-
- if m == "L": # left turn
- pyaw.append(pyaw[-1] + d)
- elif m == "S": # Straight
- pyaw.append(pyaw[-1])
- elif m == "R": # right turn
- pyaw.append(pyaw[-1] - d)
- pd += d
-
- d = l - pd
- px.append(px[-1] + d * c * math.cos(pyaw[-1]))
- py.append(py[-1] + d * c * math.sin(pyaw[-1]))
-
- if m == "L": # left turn
- pyaw.append(pyaw[-1] + d)
- elif m == "S": # Straight
- pyaw.append(pyaw[-1])
- elif m == "R": # right turn
- pyaw.append(pyaw[-1] - d)
- pd += d
-
- return px, py, pyaw
-
-
-def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover
- """
- Plot arrow
- """
-
- if not isinstance(x, float):
- for (ix, iy, iyaw) in zip(x, y, yaw):
- plot_arrow(ix, iy, iyaw)
- else:
- plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw),
- fc=fc, ec=ec, head_width=width, head_length=width)
- plt.plot(x, y)
-
-
-if __name__ == '__main__':
- print("Dubins path planner sample start!!")
-
- start_x = 1.0 # [m]
- start_y = 1.0 # [m]
- start_yaw = np.deg2rad(45.0) # [rad]
-
- end_x = -3.0 # [m]
- end_y = -3.0 # [m]
- end_yaw = np.deg2rad(-45.0) # [rad]
-
- curvature = 1.0
-
- px, py, pyaw, mode, clen = dubins_path_planning(start_x, start_y, start_yaw,
- end_x, end_y, end_yaw, curvature)
-
- plt.plot(px, py, label="final course " + "".join(mode))
-
- # plotting
- plot_arrow(start_x, start_y, start_yaw)
- plot_arrow(end_x, end_y, end_yaw)
-
- # for (ix, iy, iyaw) in zip(px, py, pyaw):
- # plot_arrow(ix, iy, iyaw, fc="b")
-
- plt.legend()
- plt.grid(True)
- plt.axis("equal")
- plt.show()
diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py
index 0494bbabef..7c52879b7c 100644
--- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py
+++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py
@@ -1,271 +1,216 @@
"""
-Path Planning Sample Code with RRT and Dubins path
+Path planning Sample Code with RRT and Dubins path
author: AtsushiSakai(@Atsushi_twi)
"""
-
-import random
-import math
import copy
-import numpy as np
-import dubins_path_planning
+import math
+import random
import matplotlib.pyplot as plt
+import numpy as np
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) # root dir
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+
+from DubinsPath import dubins_path_planner
+from RRTStar.rrt_star import RRTStar
+from utils.plot import plot_arrow
show_animation = True
-class RRT():
+class RRTStarDubins(RRTStar):
"""
- Class for RRT Planning
+ Class for RRT star planning with Dubins path
"""
- def __init__(self, start, goal, obstacleList, randArea,
- goalSampleRate=10, maxIter=100):
+ class Node(RRTStar.Node):
+ """
+ RRT Node
+ """
+
+ def __init__(self, x, y, yaw):
+ super().__init__(x, y)
+ self.yaw = yaw
+ self.path_yaw = []
+
+ def __init__(self, start, goal, obstacle_list, rand_area,
+ goal_sample_rate=10,
+ max_iter=200,
+ connect_circle_dist=50.0,
+ robot_radius=0.0,
+ ):
"""
Setting Parameter
start:Start Position [x,y]
goal:Goal Position [x,y]
obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
+ randArea:Random Sampling Area [min,max]
+ robot_radius: robot body modeled as circle with given radius
"""
- self.start = Node(start[0], start[1], start[2])
- self.end = Node(goal[0], goal[1], goal[2])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=True):
+ self.start = self.Node(start[0], start[1], start[2])
+ self.end = self.Node(goal[0], goal[1], goal[2])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.goal_sample_rate = goal_sample_rate
+ self.max_iter = max_iter
+ self.obstacle_list = obstacle_list
+ self.connect_circle_dist = connect_circle_dist
+
+ self.curvature = 1.0 # for dubins path
+ self.goal_yaw_th = np.deg2rad(1.0)
+ self.goal_xy_th = 0.5
+ self.robot_radius = robot_radius
+
+ def planning(self, animation=True, search_until_max_iter=True):
"""
- Pathplanning
+ RRT Star planning
animation: flag for animation on or off
"""
- self.nodeList = [self.start]
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.GetNearestListIndex(self.nodeList, rnd)
-
- newNode = self.steer(rnd, nind)
- # print(newNode.cost)
-
- if self.CollisionCheck(newNode, self.obstacleList):
- nearinds = self.find_near_nodes(newNode)
- newNode = self.choose_parent(newNode, nearinds)
- self.nodeList.append(newNode)
- self.rewire(newNode, nearinds)
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind], rnd)
+
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ near_indexes = self.find_near_nodes(new_node)
+ new_node = self.choose_parent(new_node, near_indexes)
+ if new_node:
+ self.node_list.append(new_node)
+ self.rewire(new_node, near_indexes)
if animation and i % 5 == 0:
- self.DrawGraph(rnd=rnd)
+ self.plot_start_goal_arrow()
+ self.draw_graph(rnd)
- # generate coruse
- lastIndex = self.get_best_last_index()
- # print(lastIndex)
+ if (not search_until_max_iter) and new_node: # check reaching the goal
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
- if lastIndex is None:
- return None
+ print("reached max iteration")
- path = self.gen_final_course(lastIndex)
- return path
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
+ else:
+ print("Cannot find path")
- def choose_parent(self, newNode, nearinds):
- if not nearinds:
- return newNode
+ return None
- dlist = []
- for i in nearinds:
- tNode = self.steer(newNode, i)
- if self.CollisionCheck(tNode, self.obstacleList):
- dlist.append(tNode.cost)
- else:
- dlist.append(float("inf"))
+ def draw_graph(self, rnd=None):
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
- mincost = min(dlist)
- minind = nearinds[dlist.index(mincost)]
+ for (ox, oy, size) in self.obstacle_list:
+ plt.plot(ox, oy, "ok", ms=30 * size)
- if mincost == float("inf"):
- print("mincost is inf")
- return newNode
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis([-2, 15, -2, 15])
+ plt.grid(True)
+ self.plot_start_goal_arrow()
+ plt.pause(0.01)
- newNode = self.steer(newNode, minind)
+ def plot_start_goal_arrow(self):
+ plot_arrow(self.start.x, self.start.y, self.start.yaw)
+ plot_arrow(self.end.x, self.end.y, self.end.yaw)
- return newNode
+ def steer(self, from_node, to_node):
- def pi_2_pi(self, angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ px, py, pyaw, mode, course_lengths = \
+ dubins_path_planner.plan_dubins_path(
+ from_node.x, from_node.y, from_node.yaw,
+ to_node.x, to_node.y, to_node.yaw, self.curvature)
- def steer(self, rnd, nind):
- # print(rnd)
- curvature = 1.0
+ if len(px) <= 1: # cannot find a dubins path
+ return None
- nearestNode = self.nodeList[nind]
+ new_node = copy.deepcopy(from_node)
+ new_node.x = px[-1]
+ new_node.y = py[-1]
+ new_node.yaw = pyaw[-1]
- px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning(
- nearestNode.x, nearestNode.y, nearestNode.yaw, rnd.x, rnd.y, rnd.yaw, curvature)
+ new_node.path_x = px
+ new_node.path_y = py
+ new_node.path_yaw = pyaw
+ new_node.cost += sum([abs(c) for c in course_lengths])
+ new_node.parent = from_node
- newNode = copy.deepcopy(nearestNode)
- newNode.x = px[-1]
- newNode.y = py[-1]
- newNode.yaw = pyaw[-1]
+ return new_node
- newNode.path_x = px
- newNode.path_y = py
- newNode.path_yaw = pyaw
- newNode.cost += clen
- newNode.parent = nind
+ def calc_new_cost(self, from_node, to_node):
- return newNode
+ _, _, _, _, course_lengths = dubins_path_planner.plan_dubins_path(
+ from_node.x, from_node.y, from_node.yaw,
+ to_node.x, to_node.y, to_node.yaw, self.curvature)
- def get_random_point(self):
+ cost = sum([abs(c) for c in course_lengths])
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand),
- random.uniform(-math.pi, math.pi)
- ]
- else: # goal point sampling
- rnd = [self.end.x, self.end.y, self.end.yaw]
+ return from_node.cost + cost
- node = Node(rnd[0], rnd[1], rnd[2])
+ def get_random_node(self):
- return node
+ if random.randint(0, 100) > self.goal_sample_rate:
+ rnd = self.Node(random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand),
+ random.uniform(-math.pi, math.pi)
+ )
+ else: # goal point sampling
+ rnd = self.Node(self.end.x, self.end.y, self.end.yaw)
- def get_best_last_index(self):
- # print("get_best_last_index")
+ return rnd
- YAWTH = np.deg2rad(1.0)
- XYTH = 0.5
+ def search_best_goal_node(self):
- goalinds = []
- for (i, node) in enumerate(self.nodeList):
- if self.calc_dist_to_goal(node.x, node.y) <= XYTH:
- goalinds.append(i)
+ goal_indexes = []
+ for (i, node) in enumerate(self.node_list):
+ if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th:
+ goal_indexes.append(i)
# angle check
- fgoalinds = []
- for i in goalinds:
- if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH:
- fgoalinds.append(i)
+ final_goal_indexes = []
+ for i in goal_indexes:
+ if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th:
+ final_goal_indexes.append(i)
- if not fgoalinds:
+ if not final_goal_indexes:
return None
- mincost = min([self.nodeList[i].cost for i in fgoalinds])
- for i in fgoalinds:
- if self.nodeList[i].cost == mincost:
+ min_cost = min([self.node_list[i].cost for i in final_goal_indexes])
+ for i in final_goal_indexes:
+ if self.node_list[i].cost == min_cost:
return i
return None
- def gen_final_course(self, goalind):
+ def generate_final_course(self, goal_index):
+ print("final")
path = [[self.end.x, self.end.y]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
+ node = self.node_list[goal_index]
+ while node.parent:
for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
path.append([ix, iy])
- # path.append([node.x, node.y])
- goalind = node.parent
+ node = node.parent
path.append([self.start.x, self.start.y])
return path
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def find_near_nodes(self, newNode):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- # r = self.expandDis * 5.0
- dlist = [(node.x - newNode.x) ** 2 +
- (node.y - newNode.y) ** 2 +
- (node.yaw - newNode.yaw) ** 2
- for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def rewire(self, newNode, nearinds):
-
- nnode = len(self.nodeList)
-
- for i in nearinds:
- nearNode = self.nodeList[i]
- tNode = self.steer(nearNode, nnode - 1)
-
- obstacleOK = self.CollisionCheck(tNode, self.obstacleList)
- imporveCost = nearNode.cost > tNode.cost
-
- if obstacleOK and imporveCost:
- # print("rewire")
- self.nodeList[i] = tNode
-
- def DrawGraph(self, rnd=None): # pragma: no cover
- """
- Draw Graph
- """
- plt.clf()
- if rnd is not None:
- plt.plot(rnd.x, rnd.y, "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot(node.path_x, node.path_y, "-g")
- # plt.plot([node.x, self.nodeList[node.parent].x], [
- # node.y, self.nodeList[node.parent].y], "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- dubins_path_planning.plot_arrow(
- self.start.x, self.start.y, self.start.yaw)
- dubins_path_planning.plot_arrow(
- self.end.x, self.end.y, self.end.yaw)
-
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- # plt.show()
- # input()
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd.x) ** 2 +
- (node.y - rnd.y) ** 2 +
- (node.yaw - rnd.yaw) ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
-
- return minind
-
- def CollisionCheck(self, node, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- for (ix, iy) in zip(node.path_x, node.path_y):
- dx = ox - ix
- dy = oy - iy
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
-
- return True # safe
-
-
-class Node():
- """
- RRT Node
- """
-
- def __init__(self, x, y, yaw):
- self.x = x
- self.y = y
- self.yaw = yaw
- self.path_x = []
- self.path_y = []
- self.path_yaw = []
- self.cost = 0.0
- self.parent = None
-
def main():
print("Start rrt star with dubins planning")
@@ -284,12 +229,12 @@ def main():
start = [0.0, 0.0, np.deg2rad(0.0)]
goal = [10.0, 10.0, np.deg2rad(0.0)]
- rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList)
- path = rrt.Planning(animation=show_animation)
+ rrtstar_dubins = RRTStarDubins(start, goal, rand_area=[-2.0, 15.0], obstacle_list=obstacleList)
+ path = rrtstar_dubins.planning(animation=show_animation)
# Draw final path
if show_animation: # pragma: no cover
- rrt.DrawGraph()
+ rrtstar_dubins.draw_graph()
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
plt.grid(True)
plt.pause(0.001)
diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py
index 489cf08709..c4c3e7c8a8 100644
--- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py
+++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py
@@ -1,289 +1,233 @@
"""
-Path Planning Sample Code with RRT for car like robot.
+Path planning Sample Code with RRT with Reeds-Shepp path
author: AtsushiSakai(@Atsushi_twi)
"""
-import matplotlib.pyplot as plt
-import numpy as np
import copy
import math
import random
import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/ReedsSheppPath/")
+import pathlib
+import matplotlib.pyplot as plt
+import numpy as np
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
-try:
- import reeds_shepp_path_planning
-except:
- raise
+from ReedsSheppPath import reeds_shepp_path_planning
+from RRTStar.rrt_star import RRTStar
show_animation = True
-STEP_SIZE = 0.1
-curvature = 1.0
-class RRT():
+class RRTStarReedsShepp(RRTStar):
"""
- Class for RRT Planning
+ Class for RRT star planning with Reeds Shepp path
"""
- def __init__(self, start, goal, obstacleList, randArea,
- goalSampleRate=10, maxIter=400):
+ class Node(RRTStar.Node):
+ """
+ RRT Node
+ """
+
+ def __init__(self, x, y, yaw):
+ super().__init__(x, y)
+ self.yaw = yaw
+ self.path_yaw = []
+
+ def __init__(self, start, goal, obstacle_list, rand_area,
+ max_iter=200, step_size=0.2,
+ connect_circle_dist=50.0,
+ robot_radius=0.0
+ ):
"""
Setting Parameter
start:Start Position [x,y]
goal:Goal Position [x,y]
obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
+ randArea:Random Sampling Area [min,max]
+ robot_radius: robot body modeled as circle with given radius
"""
- self.start = Node(start[0], start[1], start[2])
- self.end = Node(goal[0], goal[1], goal[2])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=True):
+ self.start = self.Node(start[0], start[1], start[2])
+ self.end = self.Node(goal[0], goal[1], goal[2])
+ self.min_rand = rand_area[0]
+ self.max_rand = rand_area[1]
+ self.max_iter = max_iter
+ self.step_size = step_size
+ self.obstacle_list = obstacle_list
+ self.connect_circle_dist = connect_circle_dist
+ self.robot_radius = robot_radius
+
+ self.curvature = 1.0
+ self.goal_yaw_th = np.deg2rad(1.0)
+ self.goal_xy_th = 0.5
+
+ def set_random_seed(self, seed):
+ random.seed(seed)
+
+ def planning(self, animation=True, search_until_max_iter=True):
"""
- Pathplanning
+ planning
animation: flag for animation on or off
"""
- self.nodeList = [self.start]
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.GetNearestListIndex(self.nodeList, rnd)
+ self.node_list = [self.start]
+ for i in range(self.max_iter):
+ print("Iter:", i, ", number of nodes:", len(self.node_list))
+ rnd = self.get_random_node()
+ nearest_ind = self.get_nearest_node_index(self.node_list, rnd)
+ new_node = self.steer(self.node_list[nearest_ind], rnd)
+
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ near_indexes = self.find_near_nodes(new_node)
+ new_node = self.choose_parent(new_node, near_indexes)
+ if new_node:
+ self.node_list.append(new_node)
+ self.rewire(new_node, near_indexes)
+ self.try_goal_path(new_node)
- newNode = self.steer(rnd, nind)
- if newNode is None:
- continue
+ if animation and i % 5 == 0:
+ self.plot_start_goal_arrow()
+ self.draw_graph(rnd)
- if self.CollisionCheck(newNode, self.obstacleList):
- nearinds = self.find_near_nodes(newNode)
- newNode = self.choose_parent(newNode, nearinds)
- if newNode is None:
- continue
- self.nodeList.append(newNode)
- self.rewire(newNode, nearinds)
+ if (not search_until_max_iter) and new_node: # check reaching the goal
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
- if animation and i % 5 == 0:
- self.DrawGraph(rnd=rnd)
+ print("reached max iteration")
- # generate coruse
- lastIndex = self.get_best_last_index()
- if lastIndex is None:
- return None
- path = self.gen_final_course(lastIndex)
- return path
+ last_index = self.search_best_goal_node()
+ if last_index:
+ return self.generate_final_course(last_index)
+ else:
+ print("Cannot find path")
- def choose_parent(self, newNode, nearinds):
- if not nearinds:
- return newNode
+ return None
- dlist = []
- for i in nearinds:
- tNode = self.steer(newNode, i)
- if tNode is None:
- continue
+ def try_goal_path(self, node):
- if self.CollisionCheck(tNode, self.obstacleList):
- dlist.append(tNode.cost)
- else:
- dlist.append(float("inf"))
+ goal = self.Node(self.end.x, self.end.y, self.end.yaw)
- mincost = min(dlist)
- minind = nearinds[dlist.index(mincost)]
+ new_node = self.steer(node, goal)
+ if new_node is None:
+ return
- if mincost == float("inf"):
- print("mincost is inf")
- return newNode
+ if self.check_collision(
+ new_node, self.obstacle_list, self.robot_radius):
+ self.node_list.append(new_node)
- newNode = self.steer(newNode, minind)
+ def draw_graph(self, rnd=None):
+ plt.clf()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if rnd is not None:
+ plt.plot(rnd.x, rnd.y, "^k")
+ for node in self.node_list:
+ if node.parent:
+ plt.plot(node.path_x, node.path_y, "-g")
- return newNode
+ for (ox, oy, size) in self.obstacle_list:
+ plt.plot(ox, oy, "ok", ms=30 * size)
- def pi_2_pi(self, angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ plt.plot(self.start.x, self.start.y, "xr")
+ plt.plot(self.end.x, self.end.y, "xr")
+ plt.axis([-2, 15, -2, 15])
+ plt.grid(True)
+ self.plot_start_goal_arrow()
+ plt.pause(0.01)
- def steer(self, rnd, nind):
+ def plot_start_goal_arrow(self):
+ reeds_shepp_path_planning.plot_arrow(
+ self.start.x, self.start.y, self.start.yaw)
+ reeds_shepp_path_planning.plot_arrow(
+ self.end.x, self.end.y, self.end.yaw)
- nearestNode = self.nodeList[nind]
+ def steer(self, from_node, to_node):
- px, py, pyaw, mode, clen = reeds_shepp_path_planning.reeds_shepp_path_planning(
- nearestNode.x, nearestNode.y, nearestNode.yaw, rnd.x, rnd.y, rnd.yaw, curvature, STEP_SIZE)
+ px, py, pyaw, mode, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning(
+ from_node.x, from_node.y, from_node.yaw, to_node.x,
+ to_node.y, to_node.yaw, self.curvature, self.step_size)
- if px is None:
+ if not px:
return None
- newNode = copy.deepcopy(nearestNode)
- newNode.x = px[-1]
- newNode.y = py[-1]
- newNode.yaw = pyaw[-1]
+ new_node = copy.deepcopy(from_node)
+ new_node.x = px[-1]
+ new_node.y = py[-1]
+ new_node.yaw = pyaw[-1]
+
+ new_node.path_x = px
+ new_node.path_y = py
+ new_node.path_yaw = pyaw
+ new_node.cost += sum([abs(l) for l in course_lengths])
+ new_node.parent = from_node
- newNode.path_x = px
- newNode.path_y = py
- newNode.path_yaw = pyaw
- newNode.cost += sum([abs(c) for c in clen])
- newNode.parent = nind
+ return new_node
- return newNode
+ def calc_new_cost(self, from_node, to_node):
- def get_random_point(self):
+ _, _, _, _, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning(
+ from_node.x, from_node.y, from_node.yaw, to_node.x,
+ to_node.y, to_node.yaw, self.curvature, self.step_size)
+ if not course_lengths:
+ return float("inf")
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand),
- random.uniform(-math.pi, math.pi)
- ]
- else: # goal point sampling
- rnd = [self.end.x, self.end.y, self.end.yaw]
+ return from_node.cost + sum([abs(l) for l in course_lengths])
- node = Node(rnd[0], rnd[1], rnd[2])
+ def get_random_node(self):
- return node
+ rnd = self.Node(random.uniform(self.min_rand, self.max_rand),
+ random.uniform(self.min_rand, self.max_rand),
+ random.uniform(-math.pi, math.pi)
+ )
- def get_best_last_index(self):
- # print("get_best_last_index")
+ return rnd
- YAWTH = np.deg2rad(3.0)
- XYTH = 0.5
+ def search_best_goal_node(self):
- goalinds = []
- for (i, node) in enumerate(self.nodeList):
- if self.calc_dist_to_goal(node.x, node.y) <= XYTH:
- goalinds.append(i)
- # print("OK XY TH num is")
- # print(len(goalinds))
+ goal_indexes = []
+ for (i, node) in enumerate(self.node_list):
+ if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th:
+ goal_indexes.append(i)
+ print("goal_indexes:", len(goal_indexes))
# angle check
- fgoalinds = []
- for i in goalinds:
- if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH:
- fgoalinds.append(i)
- # print("OK YAW TH num is")
- # print(len(fgoalinds))
-
- if not fgoalinds:
+ final_goal_indexes = []
+ for i in goal_indexes:
+ if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th:
+ final_goal_indexes.append(i)
+
+ print("final_goal_indexes:", len(final_goal_indexes))
+
+ if not final_goal_indexes:
return None
- mincost = min([self.nodeList[i].cost for i in fgoalinds])
- for i in fgoalinds:
- if self.nodeList[i].cost == mincost:
+ min_cost = min([self.node_list[i].cost for i in final_goal_indexes])
+ print("min_cost:", min_cost)
+ for i in final_goal_indexes:
+ if self.node_list[i].cost == min_cost:
return i
return None
- def gen_final_course(self, goalind):
- path = [[self.end.x, self.end.y]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
- for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)):
- path.append([ix, iy])
- goalind = node.parent
- path.append([self.start.x, self.start.y])
+ def generate_final_course(self, goal_index):
+ path = [[self.end.x, self.end.y, self.end.yaw]]
+ node = self.node_list[goal_index]
+ while node.parent:
+ for (ix, iy, iyaw) in zip(reversed(node.path_x), reversed(node.path_y), reversed(node.path_yaw)):
+ path.append([ix, iy, iyaw])
+ node = node.parent
+ path.append([self.start.x, self.start.y, self.start.yaw])
return path
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def find_near_nodes(self, newNode):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- # r = self.expandDis * 5.0
- dlist = [(node.x - newNode.x) ** 2 +
- (node.y - newNode.y) ** 2 +
- (node.yaw - newNode.yaw) ** 2
- for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def rewire(self, newNode, nearinds):
-
- nnode = len(self.nodeList)
-
- for i in nearinds:
- nearNode = self.nodeList[i]
- tNode = self.steer(nearNode, nnode - 1)
- if tNode is None:
- continue
-
- obstacleOK = self.CollisionCheck(tNode, self.obstacleList)
- imporveCost = nearNode.cost > tNode.cost
-
- if obstacleOK and imporveCost:
- # print("rewire")
- self.nodeList[i] = tNode
-
- def DrawGraph(self, rnd=None): # pragma: no cover
- plt.clf()
- if rnd is not None:
- plt.plot(rnd.x, rnd.y, "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot(node.path_x, node.path_y, "-g")
- # plt.plot([node.x, self.nodeList[node.parent].x], [
- # node.y, self.nodeList[node.parent].y], "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- reeds_shepp_path_planning.plot_arrow(
- self.start.x, self.start.y, self.start.yaw)
- reeds_shepp_path_planning.plot_arrow(
- self.end.x, self.end.y, self.end.yaw)
-
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- # plt.show()
- # input()
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd.x) ** 2 +
- (node.y - rnd.y) ** 2 +
- (node.yaw - rnd.yaw) ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
-
- return minind
-
- def CollisionCheck(self, node, obstacleList):
-
- for (ox, oy, size) in obstacleList:
- for (ix, iy) in zip(node.path_x, node.path_y):
- dx = ox - ix
- dy = oy - iy
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
-
- return True # safe
-
-
-class Node():
- """
- RRT Node
- """
-
- def __init__(self, x, y, yaw):
- self.x = x
- self.y = y
- self.yaw = yaw
- self.path_x = []
- self.path_y = []
- self.path_yaw = []
- self.cost = 0.0
- self.parent = None
-
-def main(maxIter=200):
+def main(max_iter=100):
print("Start " + __file__)
# ====Search Path with RRT====
@@ -303,15 +247,15 @@ def main(maxIter=200):
start = [0.0, 0.0, np.deg2rad(0.0)]
goal = [6.0, 7.0, np.deg2rad(90.0)]
- rrt = RRT(start, goal, randArea=[-2.0, 15.0],
- obstacleList=obstacleList,
- maxIter=maxIter)
- path = rrt.Planning(animation=show_animation)
+ rrt_star_reeds_shepp = RRTStarReedsShepp(start, goal,
+ obstacleList,
+ [-2.0, 15.0], max_iter=max_iter)
+ path = rrt_star_reeds_shepp.planning(animation=show_animation)
# Draw final path
- if show_animation: # pragma: no cover
- rrt.DrawGraph()
- plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
+ if path and show_animation: # pragma: no cover
+ rrt_star_reeds_shepp.draw_graph()
+ plt.plot([x for (x, y, yaw) in path], [y for (x, y, yaw) in path], '-r')
plt.grid(True)
plt.pause(0.001)
plt.show()
diff --git a/PathPlanning/RRTstar/figure_1.png b/PathPlanning/RRTstar/figure_1.png
deleted file mode 100644
index 72a4ebadf9..0000000000
Binary files a/PathPlanning/RRTstar/figure_1.png and /dev/null differ
diff --git a/PathPlanning/RRTstar/rrt_star.ipynb b/PathPlanning/RRTstar/rrt_star.ipynb
deleted file mode 100644
index 20efa46878..0000000000
--- a/PathPlanning/RRTstar/rrt_star.ipynb
+++ /dev/null
@@ -1,74 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### Simulation"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 1,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"Figure_1.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "#### Ref\n",
- "\n",
- "- [Sampling-based Algorithms for Optimal Motion Planning](https://arxiv.org/pdf/1105.1186.pdf)"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.8"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/PathPlanning/RRTstar/rrt_star.py b/PathPlanning/RRTstar/rrt_star.py
deleted file mode 100644
index 169ead8256..0000000000
--- a/PathPlanning/RRTstar/rrt_star.py
+++ /dev/null
@@ -1,285 +0,0 @@
-
-
-
-"""
-Path Planning Sample Code with RRT*
-
-author: AtsushiSakai(@Atsushi_twi)
-
-"""
-
-import random
-import math
-import copy
-import numpy as np
-import matplotlib.pyplot as plt
-
-show_animation = True
-
-
-class Node():
-
- def __init__(self, x, y):
- self.x = x
- self.y = y
- self.cost = 0.0
- self.parent = None
-
-
-class RRT():
- """
- Class for RRT Planning
- """
-
- def __init__(self, start, goal, obstacleList, randArea,
- expandDis=0.5, goalSampleRate=20, maxIter=500):
- """
- Setting Parameter
-
- start:Start Position [x,y]
- goal:Goal Position [x,y]
- obstacleList:obstacle Positions [[x,y,size],...]
- randArea:Ramdom Samping Area [min,max]
-
- """
- self.start = Node(start[0], start[1])
- self.end = Node(goal[0], goal[1])
- self.minrand = randArea[0]
- self.maxrand = randArea[1]
- self.expandDis = expandDis
- self.goalSampleRate = goalSampleRate
- self.maxIter = maxIter
- self.obstacleList = obstacleList
-
- def Planning(self, animation=True, search_until_maxiter=True):
- """
- rrt path planning
-
- animation: flag for animation on or off
- search_until_maxiter: search until max iteration for path improving or not
- """
-
- self.nodeList = [self.start]
- for i in range(self.maxIter):
- rnd = self.get_random_point()
- nind = self.GetNearestListIndex(self.nodeList, rnd)
-
- new_node = self.steer(rnd, nind)
-
- if self.__CollisionCheck(new_node, self.obstacleList):
- nearinds = self.find_near_nodes(new_node)
- new_node = self.choose_parent(new_node, nearinds)
- self.nodeList.append(new_node)
- self.rewire(new_node, nearinds)
-
- if animation and i % 5 == 0:
- self.DrawGraph(rnd)
-
- # generate course
- if not search_until_maxiter:
- lastIndex = self.get_best_last_index()
- if lastIndex:
- return self.gen_final_course(lastIndex)
-
- print("reached max iteration")
-
- lastIndex = self.get_best_last_index()
- if lastIndex:
- return self.gen_final_course(lastIndex)
-
- return None
-
- def choose_parent(self, new_node, nearinds):
- if not nearinds:
- return new_node
-
- dlist = []
- for i in nearinds:
- dx = new_node.x - self.nodeList[i].x
- dy = new_node.y - self.nodeList[i].y
- d = math.sqrt(dx ** 2 + dy ** 2)
- theta = math.atan2(dy, dx)
- if self.check_collision_extend(self.nodeList[i], theta, d):
- dlist.append(self.nodeList[i].cost + d)
- else:
- dlist.append(float("inf"))
-
- mincost = min(dlist)
- minind = nearinds[dlist.index(mincost)]
-
- if mincost == float("inf"):
- print("mincost is inf")
- return new_node
-
- new_node.cost = mincost
- new_node.parent = minind
-
- return new_node
-
- def steer(self, rnd, nind):
-
- # expand tree
- nearest_node = self.nodeList[nind]
- theta = math.atan2(rnd[1] - nearest_node.y, rnd[0] - nearest_node.x)
- new_node = Node(rnd[0], rnd[1])
- currentDistance = math.sqrt(
- (rnd[1] - nearest_node.y) ** 2 + (rnd[0] - nearest_node.x) ** 2)
- # Find a point within expandDis of nind, and closest to rnd
- if currentDistance <= self.expandDis:
- pass
- else:
- new_node.x = nearest_node.x + self.expandDis * math.cos(theta)
- new_node.y = nearest_node.y + self.expandDis * math.sin(theta)
- new_node.cost = float("inf")
- new_node.parent = None
- return new_node
-
- def get_random_point(self):
-
- if random.randint(0, 100) > self.goalSampleRate:
- rnd = [random.uniform(self.minrand, self.maxrand),
- random.uniform(self.minrand, self.maxrand)]
- else: # goal point sampling
- rnd = [self.end.x, self.end.y]
-
- return rnd
-
- def get_best_last_index(self):
-
- disglist = [self.calc_dist_to_goal(
- node.x, node.y) for node in self.nodeList]
- goalinds = [disglist.index(i) for i in disglist if i <= self.expandDis]
-
- if not goalinds:
- return None
-
- mincost = min([self.nodeList[i].cost for i in goalinds])
- for i in goalinds:
- if self.nodeList[i].cost == mincost:
- return i
-
- return None
-
- def gen_final_course(self, goalind):
- path = [[self.end.x, self.end.y]]
- while self.nodeList[goalind].parent is not None:
- node = self.nodeList[goalind]
- path.append([node.x, node.y])
- goalind = node.parent
- path.append([self.start.x, self.start.y])
- return path
-
- def calc_dist_to_goal(self, x, y):
- return np.linalg.norm([x - self.end.x, y - self.end.y])
-
- def find_near_nodes(self, new_node):
- nnode = len(self.nodeList)
- r = 50.0 * math.sqrt((math.log(nnode) / nnode))
- dlist = [(node.x - new_node.x) ** 2 +
- (node.y - new_node.y) ** 2 for node in self.nodeList]
- nearinds = [dlist.index(i) for i in dlist if i <= r ** 2]
- return nearinds
-
- def rewire(self, new_node, nearinds):
- nnode = len(self.nodeList)
- for i in nearinds:
- nearNode = self.nodeList[i]
-
- dx = new_node.x - nearNode.x
- dy = new_node.y - nearNode.y
- d = math.sqrt(dx ** 2 + dy ** 2)
-
- scost = new_node.cost + d
-
- if nearNode.cost > scost:
- theta = math.atan2(dy, dx)
- if self.check_collision_extend(nearNode, theta, d):
- nearNode.parent = nnode - 1
- nearNode.cost = scost
-
- def check_collision_extend(self, nearNode, theta, d):
-
- tmpNode = copy.deepcopy(nearNode)
-
- for i in range(int(d / self.expandDis)):
- tmpNode.x += self.expandDis * math.cos(theta)
- tmpNode.y += self.expandDis * math.sin(theta)
- if not self.__CollisionCheck(tmpNode, self.obstacleList):
- return False
-
- return True
-
- def DrawGraph(self, rnd=None):
- """
- Draw Graph
- """
- plt.clf()
- if rnd is not None:
- plt.plot(rnd[0], rnd[1], "^k")
- for node in self.nodeList:
- if node.parent is not None:
- plt.plot([node.x, self.nodeList[node.parent].x], [
- node.y, self.nodeList[node.parent].y], "-g")
-
- for (ox, oy, size) in self.obstacleList:
- plt.plot(ox, oy, "ok", ms=30 * size)
-
- plt.plot(self.start.x, self.start.y, "xr")
- plt.plot(self.end.x, self.end.y, "xr")
- plt.axis([-2, 15, -2, 15])
- plt.grid(True)
- plt.pause(0.01)
-
- def GetNearestListIndex(self, nodeList, rnd):
- dlist = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1])
- ** 2 for node in nodeList]
- minind = dlist.index(min(dlist))
-
- return minind
-
- def __CollisionCheck(self, node, obstacleList):
- for (ox, oy, size) in obstacleList:
- dx = ox - node.x
- dy = oy - node.y
- d = dx * dx + dy * dy
- if d <= size ** 2:
- return False # collision
-
- return True # safe
-
-
-def main():
- print("Start " + __file__)
-
- # ====Search Path with RRT====
- obstacleList = [
- (5, 5, 1),
- (3, 6, 2),
- (3, 8, 2),
- (3, 10, 2),
- (7, 5, 2),
- (9, 5, 2)
- ] # [x,y,size(radius)]
-
- # Set Initial parameters
- rrt = RRT(start=[0, 0], goal=[10, 10],
- randArea=[-2, 15], obstacleList=obstacleList)
- path = rrt.Planning(animation=show_animation, search_until_maxiter=False)
-
- if path is None:
- print("Cannot find path")
- else:
- print("found path!!")
-
- # Draw final path
- if show_animation:
- rrt.DrawGraph()
- plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
- plt.grid(True)
- plt.pause(0.01) # Need for Mac
- plt.show()
-
-
-if __name__ == '__main__':
- main()
-
diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py
index da1b4f3494..618d1d99ba 100644
--- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py
+++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py
@@ -3,44 +3,55 @@
Reeds Shepp path planner sample code
author Atsushi Sakai(@Atsushi_twi)
+co-author Videh Patel(@videh25) : Added the missing RS paths
"""
-import numpy as np
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+
import math
-import matplotlib.pyplot as plt
+import matplotlib.pyplot as plt
+import numpy as np
+from utils.angle import angle_mod
show_animation = True
class Path:
+ """
+ Path data container
+ """
def __init__(self):
+ # course segment length (negative value is backward segment)
self.lengths = []
+ # course segment type char ("S": straight, "L": left, "R": right)
self.ctypes = []
- self.L = 0.0
- self.x = []
- self.y = []
- self.yaw = []
- self.directions = []
+ self.L = 0.0 # Total lengths of the path
+ self.x = [] # x positions
+ self.y = [] # y positions
+ self.yaw = [] # orientations [rad]
+ self.directions = [] # directions (1:forward, -1:backward)
def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
- """
- Plot arrow
- """
-
- if not isinstance(x, float):
+ if isinstance(x, list):
for (ix, iy, iyaw) in zip(x, y, yaw):
plot_arrow(ix, iy, iyaw)
else:
- plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw),
- fc=fc, ec=ec, head_width=width, head_length=width)
+ plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw), fc=fc,
+ ec=ec, head_width=width, head_length=width)
plt.plot(x, y)
+def pi_2_pi(x):
+ return angle_mod(x)
+
def mod2pi(x):
- v = np.mod(x, 2.0 * math.pi)
+ # Be consistent with fmod in cplusplus here.
+ v = np.mod(x, np.copysign(2.0 * math.pi, x))
if v < -math.pi:
v += 2.0 * math.pi
else:
@@ -48,369 +59,381 @@ def mod2pi(x):
v -= 2.0 * math.pi
return v
-
-def SLS(x, y, phi):
- phi = mod2pi(phi)
- if y > 0.0 and phi > 0.0 and phi < math.pi * 0.99:
- xd = - y / math.tan(phi) + x
- t = xd - math.tan(phi / 2.0)
- u = phi
- v = math.sqrt((x - xd) ** 2 + y ** 2) - math.tan(phi / 2.0)
- return True, t, u, v
- elif y < 0.0 and phi > 0.0 and phi < math.pi * 0.99:
- xd = - y / math.tan(phi) + x
- t = xd - math.tan(phi / 2.0)
- u = phi
- v = -math.sqrt((x - xd) ** 2 + y ** 2) - math.tan(phi / 2.0)
- return True, t, u, v
-
- return False, 0.0, 0.0, 0.0
-
-
-def set_path(paths, lengths, ctypes):
-
+def set_path(paths, lengths, ctypes, step_size):
path = Path()
path.ctypes = ctypes
path.lengths = lengths
+ path.L = sum(np.abs(lengths))
# check same path exist
- for tpath in paths:
- typeissame = (tpath.ctypes == path.ctypes)
- if typeissame:
- if sum(tpath.lengths) - sum(path.lengths) <= 0.01:
- return paths # not insert path
-
- path.L = sum([abs(i) for i in lengths])
-
- # Base.Test.@test path.L >= 0.01
- if path.L >= 0.01:
- paths.append(path)
-
- return paths
-
+ for i_path in paths:
+ type_is_same = (i_path.ctypes == path.ctypes)
+ length_is_close = (sum(np.abs(i_path.lengths)) - path.L) <= step_size
+ if type_is_same and length_is_close:
+ return paths # same path found, so do not insert path
-def SCS(x, y, phi, paths):
- flag, t, u, v = SLS(x, y, phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["S", "L", "S"])
-
- flag, t, u, v = SLS(x, -y, -phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["S", "R", "S"])
+ # check path is long enough
+ if path.L <= step_size:
+ return paths # too short, so do not insert path
+ paths.append(path)
return paths
def polar(x, y):
- r = math.sqrt(x ** 2 + y ** 2)
+ r = math.hypot(x, y)
theta = math.atan2(y, x)
return r, theta
-def LSL(x, y, phi):
+def left_straight_left(x, y, phi):
u, t = polar(x - math.sin(phi), y - 1.0 + math.cos(phi))
- if t >= 0.0:
+ if 0.0 <= t <= math.pi:
v = mod2pi(phi - t)
- if v >= 0.0:
- return True, t, u, v
+ if 0.0 <= v <= math.pi:
+ return True, [t, u, v], ['L', 'S', 'L']
+
+ return False, [], []
+
+
+def left_straight_right(x, y, phi):
+ u1, t1 = polar(x + math.sin(phi), y - 1.0 - math.cos(phi))
+ u1 = u1 ** 2
+ if u1 >= 4.0:
+ u = math.sqrt(u1 - 4.0)
+ theta = math.atan2(2.0, u)
+ t = mod2pi(t1 + theta)
+ v = mod2pi(t - phi)
- return False, 0.0, 0.0, 0.0
+ if (t >= 0.0) and (v >= 0.0):
+ return True, [t, u, v], ['L', 'S', 'R']
+ return False, [], []
-def LRL(x, y, phi):
- u1, t1 = polar(x - math.sin(phi), y - 1.0 + math.cos(phi))
+
+def left_x_right_x_left(x, y, phi):
+ zeta = x - math.sin(phi)
+ eeta = y - 1 + math.cos(phi)
+ u1, theta = polar(zeta, eeta)
if u1 <= 4.0:
- u = -2.0 * math.asin(0.25 * u1)
- t = mod2pi(t1 + 0.5 * u + math.pi)
- v = mod2pi(phi - t + u)
+ A = math.acos(0.25 * u1)
+ t = mod2pi(A + theta + math.pi/2)
+ u = mod2pi(math.pi - 2 * A)
+ v = mod2pi(phi - t - u)
+ return True, [t, -u, v], ['L', 'R', 'L']
- if t >= 0.0 and u <= 0.0:
- return True, t, u, v
+ return False, [], []
- return False, 0.0, 0.0, 0.0
+def left_x_right_left(x, y, phi):
+ zeta = x - math.sin(phi)
+ eeta = y - 1 + math.cos(phi)
+ u1, theta = polar(zeta, eeta)
-def CCC(x, y, phi, paths):
+ if u1 <= 4.0:
+ A = math.acos(0.25 * u1)
+ t = mod2pi(A + theta + math.pi/2)
+ u = mod2pi(math.pi - 2*A)
+ v = mod2pi(-phi + t + u)
+ return True, [t, -u, -v], ['L', 'R', 'L']
- flag, t, u, v = LRL(x, y, phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["L", "R", "L"])
+ return False, [], []
- flag, t, u, v = LRL(-x, y, -phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["L", "R", "L"])
- flag, t, u, v = LRL(x, -y, -phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["R", "L", "R"])
+def left_right_x_left(x, y, phi):
+ zeta = x - math.sin(phi)
+ eeta = y - 1 + math.cos(phi)
+ u1, theta = polar(zeta, eeta)
- flag, t, u, v = LRL(-x, -y, phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["R", "L", "R"])
+ if u1 <= 4.0:
+ u = math.acos(1 - u1**2 * 0.125)
+ A = math.asin(2 * math.sin(u) / u1)
+ t = mod2pi(-A + theta + math.pi/2)
+ v = mod2pi(t - u - phi)
+ return True, [t, u, -v], ['L', 'R', 'L']
+
+ return False, [], []
+
+
+def left_right_x_left_right(x, y, phi):
+ zeta = x + math.sin(phi)
+ eeta = y - 1 - math.cos(phi)
+ u1, theta = polar(zeta, eeta)
+
+ # Solutions refering to (2 < u1 <= 4) are considered sub-optimal in paper
+ # Solutions do not exist for u1 > 4
+ if u1 <= 2:
+ A = math.acos((u1 + 2) * 0.25)
+ t = mod2pi(theta + A + math.pi/2)
+ u = mod2pi(A)
+ v = mod2pi(phi - t + 2*u)
+ if ((t >= 0) and (u >= 0) and (v >= 0)):
+ return True, [t, u, -u, -v], ['L', 'R', 'L', 'R']
+
+ return False, [], []
+
+
+def left_x_right_left_x_right(x, y, phi):
+ zeta = x + math.sin(phi)
+ eeta = y - 1 - math.cos(phi)
+ u1, theta = polar(zeta, eeta)
+ u2 = (20 - u1**2) / 16
+
+ if (0 <= u2 <= 1):
+ u = math.acos(u2)
+ A = math.asin(2 * math.sin(u) / u1)
+ t = mod2pi(theta + A + math.pi/2)
+ v = mod2pi(t - phi)
+ if (t >= 0) and (v >= 0):
+ return True, [t, -u, -u, v], ['L', 'R', 'L', 'R']
- # backwards
- xb = x * math.cos(phi) + y * math.sin(phi)
- yb = x * math.sin(phi) - y * math.cos(phi)
- # println(xb, ",", yb,",",x,",",y)
+ return False, [], []
- flag, t, u, v = LRL(xb, yb, phi)
- if flag:
- paths = set_path(paths, [v, u, t], ["L", "R", "L"])
- flag, t, u, v = LRL(-xb, yb, -phi)
- if flag:
- paths = set_path(paths, [-v, -u, -t], ["L", "R", "L"])
+def left_x_right90_straight_left(x, y, phi):
+ zeta = x - math.sin(phi)
+ eeta = y - 1 + math.cos(phi)
+ u1, theta = polar(zeta, eeta)
- flag, t, u, v = LRL(xb, -yb, -phi)
- if flag:
- paths = set_path(paths, [v, u, t], ["R", "L", "R"])
+ if u1 >= 2.0:
+ u = math.sqrt(u1**2 - 4) - 2
+ A = math.atan2(2, math.sqrt(u1**2 - 4))
+ t = mod2pi(theta + A + math.pi/2)
+ v = mod2pi(t - phi + math.pi/2)
+ if (t >= 0) and (v >= 0):
+ return True, [t, -math.pi/2, -u, -v], ['L', 'R', 'S', 'L']
- flag, t, u, v = LRL(-xb, -yb, phi)
- if flag:
- paths = set_path(paths, [-v, -u, -t], ["R", "L", "R"])
+ return False, [], []
- return paths
+def left_straight_right90_x_left(x, y, phi):
+ zeta = x - math.sin(phi)
+ eeta = y - 1 + math.cos(phi)
+ u1, theta = polar(zeta, eeta)
-def CSC(x, y, phi, paths):
- flag, t, u, v = LSL(x, y, phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["L", "S", "L"])
+ if u1 >= 2.0:
+ u = math.sqrt(u1**2 - 4) - 2
+ A = math.atan2(math.sqrt(u1**2 - 4), 2)
+ t = mod2pi(theta - A + math.pi/2)
+ v = mod2pi(t - phi - math.pi/2)
+ if (t >= 0) and (v >= 0):
+ return True, [t, u, math.pi/2, -v], ['L', 'S', 'R', 'L']
- flag, t, u, v = LSL(-x, y, -phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["L", "S", "L"])
+ return False, [], []
- flag, t, u, v = LSL(x, -y, -phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["R", "S", "R"])
- flag, t, u, v = LSL(-x, -y, phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["R", "S", "R"])
+def left_x_right90_straight_right(x, y, phi):
+ zeta = x + math.sin(phi)
+ eeta = y - 1 - math.cos(phi)
+ u1, theta = polar(zeta, eeta)
- flag, t, u, v = LSR(x, y, phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["L", "S", "R"])
+ if u1 >= 2.0:
+ t = mod2pi(theta + math.pi/2)
+ u = u1 - 2
+ v = mod2pi(phi - t - math.pi/2)
+ if (t >= 0) and (v >= 0):
+ return True, [t, -math.pi/2, -u, -v], ['L', 'R', 'S', 'R']
- flag, t, u, v = LSR(-x, y, -phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["L", "S", "R"])
+ return False, [], []
- flag, t, u, v = LSR(x, -y, -phi)
- if flag:
- paths = set_path(paths, [t, u, v], ["R", "S", "L"])
- flag, t, u, v = LSR(-x, -y, phi)
- if flag:
- paths = set_path(paths, [-t, -u, -v], ["R", "S", "L"])
+def left_straight_left90_x_right(x, y, phi):
+ zeta = x + math.sin(phi)
+ eeta = y - 1 - math.cos(phi)
+ u1, theta = polar(zeta, eeta)
- return paths
+ if u1 >= 2.0:
+ t = mod2pi(theta)
+ u = u1 - 2
+ v = mod2pi(phi - t - math.pi/2)
+ if (t >= 0) and (v >= 0):
+ return True, [t, u, math.pi/2, -v], ['L', 'S', 'L', 'R']
+ return False, [], []
+
+
+def left_x_right90_straight_left90_x_right(x, y, phi):
+ zeta = x + math.sin(phi)
+ eeta = y - 1 - math.cos(phi)
+ u1, theta = polar(zeta, eeta)
-def LSR(x, y, phi):
- u1, t1 = polar(x + math.sin(phi), y - 1.0 - math.cos(phi))
- u1 = u1 ** 2
if u1 >= 4.0:
- u = math.sqrt(u1 - 4.0)
- theta = math.atan2(2.0, u)
- t = mod2pi(t1 + theta)
+ u = math.sqrt(u1**2 - 4) - 4
+ A = math.atan2(2, math.sqrt(u1**2 - 4))
+ t = mod2pi(theta + A + math.pi/2)
v = mod2pi(t - phi)
+ if (t >= 0) and (v >= 0):
+ return True, [t, -math.pi/2, -u, -math.pi/2, v], ['L', 'R', 'S', 'L', 'R']
- if t >= 0.0 and v >= 0.0:
- return True, t, u, v
+ return False, [], []
- return False, 0.0, 0.0, 0.0
+def timeflip(travel_distances):
+ return [-x for x in travel_distances]
+
+
+def reflect(steering_directions):
+ def switch_dir(dirn):
+ if dirn == 'L':
+ return 'R'
+ elif dirn == 'R':
+ return 'L'
+ else:
+ return 'S'
+ return[switch_dir(dirn) for dirn in steering_directions]
-def generate_path(q0, q1, maxc):
+
+def generate_path(q0, q1, max_curvature, step_size):
dx = q1[0] - q0[0]
dy = q1[1] - q0[1]
dth = q1[2] - q0[2]
c = math.cos(q0[2])
s = math.sin(q0[2])
- x = (c * dx + s * dy) * maxc
- y = (-s * dx + c * dy) * maxc
+ x = (c * dx + s * dy) * max_curvature
+ y = (-s * dx + c * dy) * max_curvature
+ step_size *= max_curvature
paths = []
- paths = SCS(x, y, dth, paths)
- paths = CSC(x, y, dth, paths)
- paths = CCC(x, y, dth, paths)
+ path_functions = [left_straight_left, left_straight_right, # CSC
+ left_x_right_x_left, left_x_right_left, left_right_x_left, # CCC
+ left_right_x_left_right, left_x_right_left_x_right, # CCCC
+ left_x_right90_straight_left, left_x_right90_straight_right, # CCSC
+ left_straight_right90_x_left, left_straight_left90_x_right, # CSCC
+ left_x_right90_straight_left90_x_right] # CCSCC
+
+ for path_func in path_functions:
+ flag, travel_distances, steering_dirns = path_func(x, y, dth)
+ if flag:
+ for distance in travel_distances:
+ if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size):
+ print("Step size too large for Reeds-Shepp paths.")
+ return []
+ paths = set_path(paths, travel_distances, steering_dirns, step_size)
+
+ flag, travel_distances, steering_dirns = path_func(-x, y, -dth)
+ if flag:
+ for distance in travel_distances:
+ if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size):
+ print("Step size too large for Reeds-Shepp paths.")
+ return []
+ travel_distances = timeflip(travel_distances)
+ paths = set_path(paths, travel_distances, steering_dirns, step_size)
+
+ flag, travel_distances, steering_dirns = path_func(x, -y, -dth)
+ if flag:
+ for distance in travel_distances:
+ if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size):
+ print("Step size too large for Reeds-Shepp paths.")
+ return []
+ steering_dirns = reflect(steering_dirns)
+ paths = set_path(paths, travel_distances, steering_dirns, step_size)
+
+ flag, travel_distances, steering_dirns = path_func(-x, -y, dth)
+ if flag:
+ for distance in travel_distances:
+ if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size):
+ print("Step size too large for Reeds-Shepp paths.")
+ return []
+ travel_distances = timeflip(travel_distances)
+ steering_dirns = reflect(steering_dirns)
+ paths = set_path(paths, travel_distances, steering_dirns, step_size)
return paths
-def interpolate(ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions):
+def calc_interpolate_dists_list(lengths, step_size):
+ interpolate_dists_list = []
+ for length in lengths:
+ d_dist = step_size if length >= 0.0 else -step_size
+ interp_dists = np.arange(0.0, length, d_dist)
+ interp_dists = np.append(interp_dists, length)
+ interpolate_dists_list.append(interp_dists)
- if m == "S":
- px[ind] = ox + l / maxc * math.cos(oyaw)
- py[ind] = oy + l / maxc * math.sin(oyaw)
- pyaw[ind] = oyaw
- else: # curve
- ldx = math.sin(l) / maxc
- if m == "L": # left turn
- ldy = (1.0 - math.cos(l)) / maxc
- elif m == "R": # right turn
- ldy = (1.0 - math.cos(l)) / -maxc
- gdx = math.cos(-oyaw) * ldx + math.sin(-oyaw) * ldy
- gdy = -math.sin(-oyaw) * ldx + math.cos(-oyaw) * ldy
- px[ind] = ox + gdx
- py[ind] = oy + gdy
-
- if m == "L": # left turn
- pyaw[ind] = oyaw + l
- elif m == "R": # right turn
- pyaw[ind] = oyaw - l
-
- if l > 0.0:
- directions[ind] = 1
- else:
- directions[ind] = -1
+ return interpolate_dists_list
- return px, py, pyaw, directions
+def generate_local_course(lengths, modes, max_curvature, step_size):
+ interpolate_dists_list = calc_interpolate_dists_list(lengths, step_size * max_curvature)
-def generate_local_course(L, lengths, mode, maxc, step_size):
- npoint = math.trunc(L / step_size) + len(lengths) + 4
+ origin_x, origin_y, origin_yaw = 0.0, 0.0, 0.0
- px = [0.0 for i in range(npoint)]
- py = [0.0 for i in range(npoint)]
- pyaw = [0.0 for i in range(npoint)]
- directions = [0.0 for i in range(npoint)]
- ind = 1
+ xs, ys, yaws, directions = [], [], [], []
+ for (interp_dists, mode, length) in zip(interpolate_dists_list, modes,
+ lengths):
- if lengths[0] > 0.0:
- directions[0] = 1
- else:
- directions[0] = -1
+ for dist in interp_dists:
+ x, y, yaw, direction = interpolate(dist, length, mode,
+ max_curvature, origin_x,
+ origin_y, origin_yaw)
+ xs.append(x)
+ ys.append(y)
+ yaws.append(yaw)
+ directions.append(direction)
+ origin_x = xs[-1]
+ origin_y = ys[-1]
+ origin_yaw = yaws[-1]
- ll = 0.0
+ return xs, ys, yaws, directions
- for (m, l, i) in zip(mode, lengths, range(len(mode))):
- if l > 0.0:
- d = step_size
- else:
- d = -step_size
- # set origin state
- ox, oy, oyaw = px[ind], py[ind], pyaw[ind]
-
- ind -= 1
- if i >= 1 and (lengths[i - 1] * lengths[i]) > 0:
- pd = - d - ll
- else:
- pd = d - ll
-
- while abs(pd) <= abs(l):
- ind += 1
- px, py, pyaw, directions = interpolate(
- ind, pd, m, maxc, ox, oy, oyaw, px, py, pyaw, directions)
- pd += d
-
- ll = l - pd - d # calc remain length
-
- ind += 1
- px, py, pyaw, directions = interpolate(
- ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions)
-
- # remove unused data
- while px[-1] == 0.0:
- px.pop()
- py.pop()
- pyaw.pop()
- directions.pop()
-
- return px, py, pyaw, directions
-
-
-def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+def interpolate(dist, length, mode, max_curvature, origin_x, origin_y,
+ origin_yaw):
+ if mode == "S":
+ x = origin_x + dist / max_curvature * math.cos(origin_yaw)
+ y = origin_y + dist / max_curvature * math.sin(origin_yaw)
+ yaw = origin_yaw
+ else: # curve
+ ldx = math.sin(dist) / max_curvature
+ ldy = 0.0
+ yaw = None
+ if mode == "L": # left turn
+ ldy = (1.0 - math.cos(dist)) / max_curvature
+ yaw = origin_yaw + dist
+ elif mode == "R": # right turn
+ ldy = (1.0 - math.cos(dist)) / -max_curvature
+ yaw = origin_yaw - dist
+ gdx = math.cos(-origin_yaw) * ldx + math.sin(-origin_yaw) * ldy
+ gdy = -math.sin(-origin_yaw) * ldx + math.cos(-origin_yaw) * ldy
+ x = origin_x + gdx
+ y = origin_y + gdy
+
+ return x, y, yaw, 1 if length > 0.0 else -1
def calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size):
q0 = [sx, sy, syaw]
q1 = [gx, gy, gyaw]
- paths = generate_path(q0, q1, maxc)
+ paths = generate_path(q0, q1, maxc, step_size)
for path in paths:
- x, y, yaw, directions = generate_local_course(
- path.L, path.lengths, path.ctypes, maxc, step_size * maxc)
+ xs, ys, yaws, directions = generate_local_course(path.lengths,
+ path.ctypes, maxc,
+ step_size)
# convert global coordinate
- path.x = [math.cos(-q0[2]) * ix + math.sin(-q0[2])
- * iy + q0[0] for (ix, iy) in zip(x, y)]
- path.y = [-math.sin(-q0[2]) * ix + math.cos(-q0[2])
- * iy + q0[1] for (ix, iy) in zip(x, y)]
- path.yaw = [pi_2_pi(iyaw + q0[2]) for iyaw in yaw]
+ path.x = [math.cos(-q0[2]) * ix + math.sin(-q0[2]) * iy + q0[0] for
+ (ix, iy) in zip(xs, ys)]
+ path.y = [-math.sin(-q0[2]) * ix + math.cos(-q0[2]) * iy + q0[1] for
+ (ix, iy) in zip(xs, ys)]
+ path.yaw = [pi_2_pi(yaw + q0[2]) for yaw in yaws]
path.directions = directions
- path.lengths = [l / maxc for l in path.lengths]
+ path.lengths = [length / maxc for length in path.lengths]
path.L = path.L / maxc
- # print(paths)
-
return paths
-def reeds_shepp_path_planning(sx, sy, syaw,
- gx, gy, gyaw, maxc, step_size):
-
+def reeds_shepp_path_planning(sx, sy, syaw, gx, gy, gyaw, maxc, step_size=0.2):
paths = calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size)
-
if not paths:
- # print("No path")
- # print(sx, sy, syaw, gx, gy, gyaw)
- return None, None, None, None, None
-
- minL = float("Inf")
- best_path_index = -1
- for i, _ in enumerate(paths):
- if paths[i].L <= minL:
- minL = paths[i].L
- best_path_index = i
-
- bpath = paths[best_path_index]
-
- return bpath.x, bpath.y, bpath.yaw, bpath.ctypes, bpath.lengths
-
-
-def test():
-
- NTEST = 5
-
- for i in range(NTEST):
- start_x = (np.random.rand() - 0.5) * 10.0 # [m]
- start_y = (np.random.rand() - 0.5) * 10.0 # [m]
- start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+ return None, None, None, None, None # could not generate any path
- end_x = (np.random.rand() - 0.5) * 10.0 # [m]
- end_y = (np.random.rand() - 0.5) * 10.0 # [m]
- end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+ # search minimum cost path
+ best_path_index = paths.index(min(paths, key=lambda p: abs(p.L)))
+ b_path = paths[best_path_index]
- curvature = 1.0 / (np.random.rand() * 20.0)
- step_size = 0.1
-
- px, py, pyaw, mode, clen = reeds_shepp_path_planning(
- start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature, step_size)
-
- if show_animation: # pragma: no cover
- plt.cla()
- plt.plot(px, py, label="final course " + str(mode))
-
- # plotting
- plot_arrow(start_x, start_y, start_yaw)
- plot_arrow(end_x, end_y, end_yaw)
-
- plt.legend()
- plt.grid(True)
- plt.axis("equal")
- plt.xlim(-10, 10)
- plt.ylim(-10, 10)
- plt.pause(1.0)
-
- # plt.show()
-
- print("Test done")
+ return b_path.x, b_path.y, b_path.yaw, b_path.ctypes, b_path.lengths
def main():
@@ -424,15 +447,22 @@ def main():
end_y = 5.0 # [m]
end_yaw = np.deg2rad(25.0) # [rad]
- curvature = 1.0
- step_size = 0.1
+ curvature = 0.1
+ step_size = 0.05
+
+ xs, ys, yaws, modes, lengths = reeds_shepp_path_planning(start_x, start_y,
+ start_yaw, end_x,
+ end_y, end_yaw,
+ curvature,
+ step_size)
- px, py, pyaw, mode, clen = reeds_shepp_path_planning(
- start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature, step_size)
+ if not xs:
+ assert False, "No path"
if show_animation: # pragma: no cover
plt.cla()
- plt.plot(px, py, label="final course " + str(mode))
+ plt.plot(xs, ys, label="final course " + str(modes))
+ print(f"{lengths=}")
# plotting
plot_arrow(start_x, start_y, start_yaw)
@@ -443,10 +473,6 @@ def main():
plt.axis("equal")
plt.show()
- if not px:
- assert False, "No path"
-
if __name__ == '__main__':
- test()
main()
diff --git a/PathPlanning/SpiralSpanningTreeCPP/map/test.png b/PathPlanning/SpiralSpanningTreeCPP/map/test.png
new file mode 100644
index 0000000000..4abca0bf30
Binary files /dev/null and b/PathPlanning/SpiralSpanningTreeCPP/map/test.png differ
diff --git a/PathPlanning/SpiralSpanningTreeCPP/map/test_2.png b/PathPlanning/SpiralSpanningTreeCPP/map/test_2.png
new file mode 100644
index 0000000000..0d27fa9f95
Binary files /dev/null and b/PathPlanning/SpiralSpanningTreeCPP/map/test_2.png differ
diff --git a/PathPlanning/SpiralSpanningTreeCPP/map/test_3.png b/PathPlanning/SpiralSpanningTreeCPP/map/test_3.png
new file mode 100644
index 0000000000..1a50b87ccf
Binary files /dev/null and b/PathPlanning/SpiralSpanningTreeCPP/map/test_3.png differ
diff --git a/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py b/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py
new file mode 100644
index 0000000000..a8c513e6b1
--- /dev/null
+++ b/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py
@@ -0,0 +1,313 @@
+"""
+Spiral Spanning Tree Coverage Path Planner
+
+author: Todd Tang
+paper: Spiral-STC: An On-Line Coverage Algorithm of Grid Environments
+ by a Mobile Robot - Gabriely et.al.
+link: https://ieeexplore.ieee.org/abstract/document/1013479
+"""
+
+import os
+import sys
+import math
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+do_animation = True
+
+
+class SpiralSpanningTreeCoveragePlanner:
+ def __init__(self, occ_map):
+ self.origin_map_height = occ_map.shape[0]
+ self.origin_map_width = occ_map.shape[1]
+
+ # original map resolution must be even
+ if self.origin_map_height % 2 == 1 or self.origin_map_width % 2 == 1:
+ sys.exit('original map width/height must be even \
+ in grayscale .png format')
+
+ self.occ_map = occ_map
+ self.merged_map_height = self.origin_map_height // 2
+ self.merged_map_width = self.origin_map_width // 2
+
+ self.edge = []
+
+ def plan(self, start):
+ """plan
+
+ performing Spiral Spanning Tree Coverage path planning
+
+ :param start: the start node of Spiral Spanning Tree Coverage
+ """
+
+ visit_times = np.zeros(
+ (self.merged_map_height, self.merged_map_width), dtype=int)
+ visit_times[start[0]][start[1]] = 1
+
+ # generate route by
+ # recusively call perform_spanning_tree_coverage() from start node
+ route = []
+ self.perform_spanning_tree_coverage(start, visit_times, route)
+
+ path = []
+ # generate path from route
+ for idx in range(len(route)-1):
+ dp = abs(route[idx][0] - route[idx+1][0]) + \
+ abs(route[idx][1] - route[idx+1][1])
+ if dp == 0:
+ # special handle for round-trip path
+ path.append(self.get_round_trip_path(route[idx-1], route[idx]))
+ elif dp == 1:
+ path.append(self.move(route[idx], route[idx+1]))
+ elif dp == 2:
+ # special handle for non-adjacent route nodes
+ mid_node = self.get_intermediate_node(route[idx], route[idx+1])
+ path.append(self.move(route[idx], mid_node))
+ path.append(self.move(mid_node, route[idx+1]))
+ else:
+ sys.exit('adjacent path node distance larger than 2')
+
+ return self.edge, route, path
+
+ def perform_spanning_tree_coverage(self, current_node, visit_times, route):
+ """perform_spanning_tree_coverage
+
+ recursive function for function
+
+ :param current_node: current node
+ """
+
+ def is_valid_node(i, j):
+ is_i_valid_bounded = 0 <= i < self.merged_map_height
+ is_j_valid_bounded = 0 <= j < self.merged_map_width
+ if is_i_valid_bounded and is_j_valid_bounded:
+ # free only when the 4 sub-cells are all free
+ return bool(
+ self.occ_map[2*i][2*j]
+ and self.occ_map[2*i+1][2*j]
+ and self.occ_map[2*i][2*j+1]
+ and self.occ_map[2*i+1][2*j+1])
+
+ return False
+
+ # counter-clockwise neighbor finding order
+ order = [[1, 0], [0, 1], [-1, 0], [0, -1]]
+
+ found = False
+ route.append(current_node)
+ for inc in order:
+ ni, nj = current_node[0] + inc[0], current_node[1] + inc[1]
+ if is_valid_node(ni, nj) and visit_times[ni][nj] == 0:
+ neighbor_node = (ni, nj)
+ self.edge.append((current_node, neighbor_node))
+ found = True
+ visit_times[ni][nj] += 1
+ self.perform_spanning_tree_coverage(
+ neighbor_node, visit_times, route)
+
+ # backtrace route from node with neighbors all visited
+ # to first node with unvisited neighbor
+ if not found:
+ has_node_with_unvisited_ngb = False
+ for node in reversed(route):
+ # drop nodes that have been visited twice
+ if visit_times[node[0]][node[1]] == 2:
+ continue
+
+ visit_times[node[0]][node[1]] += 1
+ route.append(node)
+
+ for inc in order:
+ ni, nj = node[0] + inc[0], node[1] + inc[1]
+ if is_valid_node(ni, nj) and visit_times[ni][nj] == 0:
+ has_node_with_unvisited_ngb = True
+ break
+
+ if has_node_with_unvisited_ngb:
+ break
+
+ return route
+
+ def move(self, p, q):
+ direction = self.get_vector_direction(p, q)
+ # move east
+ if direction == 'E':
+ p = self.get_sub_node(p, 'SE')
+ q = self.get_sub_node(q, 'SW')
+ # move west
+ elif direction == 'W':
+ p = self.get_sub_node(p, 'NW')
+ q = self.get_sub_node(q, 'NE')
+ # move south
+ elif direction == 'S':
+ p = self.get_sub_node(p, 'SW')
+ q = self.get_sub_node(q, 'NW')
+ # move north
+ elif direction == 'N':
+ p = self.get_sub_node(p, 'NE')
+ q = self.get_sub_node(q, 'SE')
+ else:
+ sys.exit('move direction error...')
+ return [p, q]
+
+ def get_round_trip_path(self, last, pivot):
+ direction = self.get_vector_direction(last, pivot)
+ if direction == 'E':
+ return [self.get_sub_node(pivot, 'SE'),
+ self.get_sub_node(pivot, 'NE')]
+ elif direction == 'S':
+ return [self.get_sub_node(pivot, 'SW'),
+ self.get_sub_node(pivot, 'SE')]
+ elif direction == 'W':
+ return [self.get_sub_node(pivot, 'NW'),
+ self.get_sub_node(pivot, 'SW')]
+ elif direction == 'N':
+ return [self.get_sub_node(pivot, 'NE'),
+ self.get_sub_node(pivot, 'NW')]
+ else:
+ sys.exit('get_round_trip_path: last->pivot direction error.')
+
+ def get_vector_direction(self, p, q):
+ # east
+ if p[0] == q[0] and p[1] < q[1]:
+ return 'E'
+ # west
+ elif p[0] == q[0] and p[1] > q[1]:
+ return 'W'
+ # south
+ elif p[0] < q[0] and p[1] == q[1]:
+ return 'S'
+ # north
+ elif p[0] > q[0] and p[1] == q[1]:
+ return 'N'
+ else:
+ sys.exit('get_vector_direction: Only E/W/S/N direction supported.')
+
+ def get_sub_node(self, node, direction):
+ if direction == 'SE':
+ return [2*node[0]+1, 2*node[1]+1]
+ elif direction == 'SW':
+ return [2*node[0]+1, 2*node[1]]
+ elif direction == 'NE':
+ return [2*node[0], 2*node[1]+1]
+ elif direction == 'NW':
+ return [2*node[0], 2*node[1]]
+ else:
+ sys.exit('get_sub_node: sub-node direction error.')
+
+ def get_interpolated_path(self, p, q):
+ # direction p->q: southwest / northeast
+ if (p[0] < q[0]) ^ (p[1] < q[1]):
+ ipx = [p[0], p[0], q[0]]
+ ipy = [p[1], q[1], q[1]]
+ # direction p->q: southeast / northwest
+ else:
+ ipx = [p[0], q[0], q[0]]
+ ipy = [p[1], p[1], q[1]]
+ return ipx, ipy
+
+ def get_intermediate_node(self, p, q):
+ p_ngb, q_ngb = set(), set()
+
+ for m, n in self.edge:
+ if m == p:
+ p_ngb.add(n)
+ if n == p:
+ p_ngb.add(m)
+ if m == q:
+ q_ngb.add(n)
+ if n == q:
+ q_ngb.add(m)
+
+ itsc = p_ngb.intersection(q_ngb)
+ if len(itsc) == 0:
+ sys.exit('get_intermediate_node: \
+ no intermediate node between', p, q)
+ elif len(itsc) == 1:
+ return list(itsc)[0]
+ else:
+ sys.exit('get_intermediate_node: \
+ more than 1 intermediate node between', p, q)
+
+ def visualize_path(self, edge, path, start):
+ def coord_transform(p):
+ return [2*p[1] + 0.5, 2*p[0] + 0.5]
+
+ if do_animation:
+ last = path[0][0]
+ trajectory = [[last[1]], [last[0]]]
+ for p, q in path:
+ distance = math.hypot(p[0]-last[0], p[1]-last[1])
+ if distance <= 1.0:
+ trajectory[0].append(p[1])
+ trajectory[1].append(p[0])
+ else:
+ ipx, ipy = self.get_interpolated_path(last, p)
+ trajectory[0].extend(ipy)
+ trajectory[1].extend(ipx)
+
+ last = q
+
+ trajectory[0].append(last[1])
+ trajectory[1].append(last[0])
+
+ for idx, state in enumerate(np.transpose(trajectory)):
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
+ # draw spanning tree
+ plt.imshow(self.occ_map, 'gray')
+ for p, q in edge:
+ p = coord_transform(p)
+ q = coord_transform(q)
+ plt.plot([p[0], q[0]], [p[1], q[1]], '-oc')
+ sx, sy = coord_transform(start)
+ plt.plot([sx], [sy], 'pr', markersize=10)
+
+ # draw move path
+ plt.plot(trajectory[0][:idx+1], trajectory[1][:idx+1], '-k')
+ plt.plot(state[0], state[1], 'or')
+ plt.axis('equal')
+ plt.grid(True)
+ plt.pause(0.01)
+
+ else:
+ # draw spanning tree
+ plt.imshow(self.occ_map, 'gray')
+ for p, q in edge:
+ p = coord_transform(p)
+ q = coord_transform(q)
+ plt.plot([p[0], q[0]], [p[1], q[1]], '-oc')
+ sx, sy = coord_transform(start)
+ plt.plot([sx], [sy], 'pr', markersize=10)
+
+ # draw move path
+ last = path[0][0]
+ for p, q in path:
+ distance = math.hypot(p[0]-last[0], p[1]-last[1])
+ if distance == 1.0:
+ plt.plot([last[1], p[1]], [last[0], p[0]], '-k')
+ else:
+ ipx, ipy = self.get_interpolated_path(last, p)
+ plt.plot(ipy, ipx, '-k')
+ plt.arrow(p[1], p[0], q[1]-p[1], q[0]-p[0], head_width=0.2)
+ last = q
+
+ plt.show()
+
+
+def main():
+ dir_path = os.path.dirname(os.path.realpath(__file__))
+ img = plt.imread(os.path.join(dir_path, 'map', 'test_2.png'))
+ STC_planner = SpiralSpanningTreeCoveragePlanner(img)
+ start = (10, 0)
+ edge, route, path = STC_planner.plan(start)
+ STC_planner.visualize_path(edge, path, start)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/StateLatticePlanner/lookup_table.csv b/PathPlanning/StateLatticePlanner/lookup_table.csv
new file mode 100644
index 0000000000..2c48a11a18
--- /dev/null
+++ b/PathPlanning/StateLatticePlanner/lookup_table.csv
@@ -0,0 +1,82 @@
+x,y,yaw,s,km,kf
+1.0,0.0,0.0,1.0,0.0,0.0
+9.975352133559392,0.0482183513545736,0.5660837104214496,10.00000000000002,0.0015736624607596847,0.31729782170754367
+15.021899857204536,0.023109001221800096,0.541061424167431,15.128443053611093,0.0006480950273134919,0.20847475849103875
+20.062147834064536,0.0406648159648112,0.5374967866814861,20.205553097986094,0.000452860235044122,0.15502921850050788
+24.924468605496358,-0.04047324014767662,0.5146575311501209,25.16775431470035,6.940620839146646e-05,0.12259452810198132
+9.971782095506931,1.9821448683146543,0.5206511572266477,10.287478424823748,0.05861430948618236,0.07036494964262185
+15.00170010872385,2.0003864283110473,0.5236741185892617,15.245993376540827,0.02657730439557895,0.09933479864250763
+19.991716537639487,1.9940629519465154,0.5226444441451559,20.277923997037238,0.015108540596275507,0.09478988637993524
+24.946447973869596,2.0815930190993206,0.5306354765686239,25.20115925294013,0.010036251429787917,0.08505936469481987
+10.033694822745312,3.9724800521928056,0.5349578864544497,11.087694168363686,0.10279429366023954,-0.12501011715795404
+15.010712586144749,4.0046776414868095,0.5234972445048012,15.729582155835587,0.05010930398580602,-0.0008557723200034717
+19.9175798257299,4.053680042954521,0.5265397234296523,20.52466275843717,0.029584390559990882,0.035276591227371874
+24.98769016158626,3.991699950598091,0.5229000018897194,25.543297770996556,0.018800715817231053,0.04750751098144048
+10.018665105170687,6.004814533505462,0.5183921334245007,12.249438857228967,0.13207408248643182,-0.2742892277307502
+14.988626131330372,5.991226410357179,0.5248160422552801,16.53593823576699,0.06924423592936522,-0.08634227857486092
+20.014420271646646,6.006767110727591,0.5233060851224174,21.23271362632659,0.041402041787912916,-0.01770377839603589
+24.998338724667267,5.997352722087869,0.5235621854299422,26.009046544833613,0.027285850882345728,0.011507045054418165
+10.040118020822444,8.017131894913126,0.5076867575242261,13.8061261785273,0.14561700178565884,-0.3527538468214878
+14.96397914886416,7.974972375534203,0.5303378183744862,17.667338175004062,0.08318912494381935,-0.15372672981944802
+20.045725182938817,8.023486945646207,0.5201839069343577,22.126364299043573,0.05173969669894265,-0.06557547083017647
+25.004687466358227,8.00036398460779,0.5234938146870878,26.740089158520917,0.034867425244601645,-0.02199309906456302
+10.065138949829214,10.03244363616002,0.49375882493214895,15.701940360254637,0.14847998727328912,-0.39355037236614626
+15.05373212031198,10.026401491912143,0.5111826366036252,19.105461052226858,0.09205576730549936,-0.20458802229704312
+19.965550451103926,9.977668905006206,0.5278605653376056,23.14082140870299,0.06010674632014157,-0.10340577652521214
+25.04062496016141,9.956781577401756,0.5252395961316738,27.641194908523495,0.04115083532669924,-0.05054407239730677
+9.980172344087242,11.981944953180841,0.5354924711458446,17.764377273124804,0.14616069587267325,-0.40115138946106776
+15.031707905116134,12.011530784459552,0.5157261778129998,20.745000892047745,0.0970285785481706,-0.2379719980195133
+20.05384921212195,12.02621662711961,0.5153884987125119,24.513013940487117,0.06601543941341544,-0.13666530932375262
+25.04326204059146,12.019946808479768,0.5198699857547844,28.74306622689766,0.04671545692054678,-0.07827401225777673
+10.005005976167096,13.993516346269931,0.5249997047973469,20.063732124124442,0.14007166951362482,-0.39994549637994103
+15.013469777117386,13.998572375088138,0.5211760827701193,22.591299061495683,0.0989196134377572,-0.25909446951756165
+19.980150236409695,13.98233838451409,0.5278966095736082,25.971685915503254,0.07029833263412807,-0.15993299513197096
+25.009669110020404,14.000751236643762,0.5227555344229664,29.949071374991423,0.05106114063333748,-0.09952052168406796
+9.996712859814979,15.986637217372996,0.5301458018536311,22.47478825250167,0.1329741433122606,-0.38823042580907063
+15.02373126750475,16.00384009060484,0.5182833077580984,24.557463511123004,0.0989491582793761,-0.26836010532851323
+20.023756339113735,16.004847752803656,0.5197401980953318,27.669260302891157,0.07275720314277462,-0.178811991371391
+25.015003771679122,16.002919774604504,0.5219791758565742,31.36524983655211,0.05429827198598215,-0.11766440355003502
+10.078596822781892,18.025309925487992,0.49768408992179225,25.02580432036455,0.1252233187334947,-0.3747545825918585
+15.001968473293188,17.988033772017467,0.5262415135796346,26.67625473617623,0.09746306394892065,-0.27167606206451594
+20.026047062413117,18.00445752595148,0.5193568548054093,29.442158339897595,0.07417227896231118,-0.19015828496001386
+24.984711558393403,17.982744830235063,0.5266809346220684,32.855828700083094,0.05675308229799072,-0.13090299334069386
+9.999999973554228,8.906672256498078e-05,-0.00024912926939091307,9.993250237275609,1.9794429093204823e-06,-0.00016167063578544257
+14.999999988951053,0.00030609885737583985,-9.259737492950393e-05,14.939586274030715,4.066161982234725e-06,-5.3230908443270726e-05
+19.999999963637627,0.0008196433029304879,-0.00010277758318455454,19.985770355960977,6.0902800817987275e-06,-5.581407356116362e-05
+24.999999906323,0.001558015443394581,-0.0001252423879458675,24.925430653319882,7.508303551937611e-06,-5.98269885073166e-05
+9.93201732790474,1.9700581591656137,-0.006606314895513332,10.1625049701131,0.05795554613825405,-0.23594780459354886
+15.017121844754504,2.000131018972639,-0.001958259181754851,15.130494387563031,0.026367577418638183,-0.10529363184139814
+19.962697589600058,2.0003823634817484,0.0021983556339688626,20.055058569558643,0.014972854970102445,-0.0592998512022201
+24.990093248087035,2.0008914594513647,0.0003319006512292333,25.020899019312747,0.009609456446194334,-0.03808543941908436
+9.942924437331126,3.9434423219621073,-0.047789349898090805,10.916318098481405,0.10417074854184473,-0.42509733550937057
+14.976393375378994,3.9987876606083557,0.004653465622298736,15.69826778341493,0.04981535482126709,-0.20027162173052074
+19.954160472557877,4.000101578371634,0.0053292950039418585,20.459066225465484,0.02905576509783228,-0.11479451096219842
+25.06247590490118,3.9997579161047643,-0.00486183691237807,25.40723367563786,0.01874893916371208,-0.07533000027879669
+9.974854017566281,5.998183884411291,0.01394025812352817,12.27808815775426,0.13163310345287574,-0.5111693653344966
+14.99829771854157,5.999020207860274,0.0007330116466723879,16.57520987140955,0.06880393034208837,-0.27508456151767885
+19.98389776689381,5.999506195067484,0.002770060727207646,21.17690590277397,0.04131547230609369,-0.1652252863196287
+25.022089217041394,5.998166050230614,-0.002551136444779001,25.974625009044832,0.02718132258204399,-0.10978755041013998
+9.940106683734614,7.99448983539684,0.03735909486314526,13.864600506318645,0.14554135993596395,-0.5498471044599721
+15.015405965817797,7.996301502316838,-0.004430455799697253,17.779484729664652,0.08234534796805798,-0.3300198333333338
+19.965919061860355,7.998456498324741,0.00732927315681664,22.0665101267907,0.05178054118886435,-0.20507088323830897
+24.97580637673196,7.998036396987909,0.0034859866489540536,26.699711792661176,0.03478260921646504,-0.13959734880932403
+10.003237328881212,9.994037173180942,-0.002542633641336778,15.800576175296408,0.1482242831571022,-0.5606578442626601
+14.95848212484301,9.995827033229693,0.016804720248816185,19.19635868417634,0.09159937492256161,-0.3610497877526804
+20.018365340632464,9.997789133099982,-0.003880405312526758,23.259977677838524,0.05967179836565363,-0.23873172503708404
+25.034844162753302,9.996613275552045,-0.005490232481425661,27.647073656497884,0.04122997694830456,-0.16548182742762063
+10.041413516307436,11.988808245039152,-0.015743247245750158,18.0174427655263,0.14424296158815444,-0.5545987939832356
+15.0710608536628,11.993636485613393,-0.025235844052727163,20.92474299071291,0.0960774359909814,-0.38199459745149106
+20.061838597733104,11.995243972143648,-0.015325438311212025,24.63090823780847,0.06556771814265559,-0.2626353022718591
+24.90813949494271,11.995929681233529,0.01760171116909426,28.6986397040137,0.046810556161518815,-0.1847353186190147
+10.005191819464756,13.97797567430312,0.018961636911005275,20.358534835690133,0.13825179056925302,-0.5307789523538471
+14.978392340358946,13.991362718235834,0.012411272386128935,22.755419658274054,0.0984622955030996,-0.38447788120958937
+20.015767113356507,13.992558840024987,-0.002205036951612893,26.18420998778461,0.06961025144239422,-0.2786494668163888
+25.01318440442437,13.994258255793202,-0.0016239998449329995,30.09124393513656,0.05071043613803722,-0.20387658283659768
+10.038844117562423,15.966797017942504,0.016384527088525225,22.88736140380268,0.13044436631301143,-0.5070826347325453
+14.91898245890566,15.984279670640529,0.03784081306841358,24.796728185207627,0.09830913950807817,-0.38207974071854045
+19.999487117727806,15.99041117221354,0.0034823225688951354,27.881676426972927,0.07220430103629995,-0.2873083396987492
+25.056418472201756,15.995103453935709,-0.011257522827095023,31.50238694595278,0.05406499488342877,-0.21526296035737832
+10.076107447676621,17.952889979512353,0.017798231103724138,25.454959881832874,0.1231232463335769,-0.47600174850950705
+15.032725028551983,17.978015286760307,0.0020752804670070013,27.089888269358894,0.09590219542773218,-0.3801465515462427
+20.03544756240551,17.98685790169768,-0.005300968094156033,29.75070206477736,0.07340450527104486,-0.29182757725382324
+24.960019173190652,17.98909417109214,0.011594018486178026,33.0995680641525,0.05634561447882407,-0.22402297280749597
diff --git a/PathPlanning/StateLatticePlanner/lookuptable.csv b/PathPlanning/StateLatticePlanner/lookuptable.csv
deleted file mode 100644
index 85eff9b932..0000000000
--- a/PathPlanning/StateLatticePlanner/lookuptable.csv
+++ /dev/null
@@ -1,25 +0,0 @@
-x,y,yaw,s,km,kf
-1.0,0.0,0.0,1.0,0.0,0.0
-0.9734888894493215,-0.009758406565994977,0.5358080146312756,0.9922329557399788,-0.10222538550473198,3.0262632253145982
-10.980728996433243,-0.0003093605787364978,0.522622783944529,11.000391678142623,0.00010296091030877934,0.2731556687244648
-16.020309241920156,0.0001292339008200291,0.5243399938698222,16.100019813021202,0.00013263212395994706,0.18999138959173634
-20.963495745193626,-0.00033031017429944326,0.5226120033275024,21.10082901143343,0.00011687467551566884,0.14550546012583987
-6.032553475650599,2.008504211720188,0.5050517859971599,6.400329805864408,0.1520002249689879,-0.13105940607691127
-10.977487445230075,2.0078696810700034,0.5263634407901872,11.201040572298973,0.04895863722280565,0.08356555007223682
-15.994057699325753,2.025659106131227,0.5303858891065698,16.200300421483128,0.0235708657178127,0.10002225103921249
-20.977228843605943,2.0281289825388513,0.5300376140865567,21.20043308669372,0.013795675421657671,0.09331700188063087
-25.95453914157977,1.9926432818499131,0.5226203078411618,26.200880299840527,0.00888830054451281,0.0830622000626594
-0.9999999999999999,0.0,0.0,1.0,0.0,0.0
-5.999999999670752,5.231312388722274e-05,1.4636120911014667e-05,5.996117185283419,4.483756968024291e-06,-3.4422519205046243e-06
-10.999749470720566,-0.011978787043239986,0.022694802592583763,10.99783855994015,-0.00024209503125174496,0.01370491008661795
-15.999885224357776,-0.018937230084507616,0.011565580878015763,15.99839381389597,-0.0002086399372890716,0.005267247862667496
-20.999882688881286,-0.030304200126461317,0.009117836885732596,20.99783120184498,-0.00020013159571184735,0.0034529188783636866
-25.999911270030413,-0.025754431694664327,0.0074809531598503615,25.99674782258235,-0.0001111138115390646,0.0021946603965658368
-10.952178818975062,1.993067260835455,0.0045572480669707136,11.17961498195845,0.04836813285436623,-0.19328716251760758
-16.028306009258,2.0086286208315407,0.009306594796759554,16.122411866381054,0.02330689045417979,-0.08877002085985948
-20.971603115419715,1.9864158336174966,0.007016819403167119,21.093006725076872,0.013439123130720928,-0.05238318300611623
-25.997019676818372,1.9818581321430093,0.007020172975955249,26.074021794586585,0.00876496148602802,-0.03362579291686346
-16.017903482982604,4.009490840390534,-5.293114796312698e-05,16.600937712976638,0.044543450568614244,-0.17444651314466567
-20.98845988414163,3.956600199823583,-0.01050744134070728,21.40149119463485,0.02622674388276059,-0.10625681152519345
-25.979448381017914,3.9968223055054977,-0.00012819253386682928,26.30504721211744,0.017467093413146118,-0.06914750106424669
-25.96268055563514,5.9821266846168,4.931311239565056e-05,26.801388563459287,0.025426008913226557,-0.10047663078001536
diff --git a/PathPlanning/StateLatticePlanner/state_lattice_planner.py b/PathPlanning/StateLatticePlanner/state_lattice_planner.py
index 424609064d..554cd0f3b7 100644
--- a/PathPlanning/StateLatticePlanner/state_lattice_planner.py
+++ b/PathPlanning/StateLatticePlanner/state_lattice_planner.py
@@ -4,39 +4,44 @@
author: Atsushi Sakai (@Atsushi_twi)
+- plookuptable.csv is generated with this script:
+https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathPlanning
+/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py
+
+Reference:
+
+- State Space Sampling of Feasible Motions for High-Performance Mobile Robot
+Navigation in Complex Environments
+https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf
+&doi=e2256b5b24137f89e473f01df288cb3aa72e56a0
+
"""
import sys
import os
from matplotlib import pyplot as plt
import numpy as np
import math
-import pandas as pd
+import pathlib
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../ModelPredictiveTrajectoryGenerator/")
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+import ModelPredictiveTrajectoryGenerator.trajectory_generator as planner
+import ModelPredictiveTrajectoryGenerator.motion_model as motion_model
-try:
- import model_predictive_trajectory_generator as planner
- import motion_model
-except:
- raise
-
-
-table_path = os.path.dirname(os.path.abspath(__file__)) + "/lookuptable.csv"
+TABLE_PATH = os.path.dirname(os.path.abspath(__file__)) + "/lookup_table.csv"
show_animation = True
-def search_nearest_one_from_lookuptable(tx, ty, tyaw, lookup_table):
+def search_nearest_one_from_lookup_table(t_x, t_y, t_yaw, lookup_table):
mind = float("inf")
minid = -1
for (i, table) in enumerate(lookup_table):
-
- dx = tx - table[0]
- dy = ty - table[1]
- dyaw = tyaw - table[2]
+ dx = t_x - table[0]
+ dy = t_y - table[1]
+ dyaw = t_yaw - table[2]
d = math.sqrt(dx ** 2 + dy ** 2 + dyaw ** 2)
if d <= mind:
minid = i
@@ -45,31 +50,29 @@ def search_nearest_one_from_lookuptable(tx, ty, tyaw, lookup_table):
return lookup_table[minid]
-def get_lookup_table():
- data = pd.read_csv(table_path)
-
- return np.array(data)
+def get_lookup_table(table_path):
+ return np.loadtxt(table_path, delimiter=',', skiprows=1)
def generate_path(target_states, k0):
# x, y, yaw, s, km, kf
- lookup_table = get_lookup_table()
+ lookup_table = get_lookup_table(TABLE_PATH)
result = []
for state in target_states:
- bestp = search_nearest_one_from_lookuptable(
+ bestp = search_nearest_one_from_lookup_table(
state[0], state[1], state[2], lookup_table)
target = motion_model.State(x=state[0], y=state[1], yaw=state[2])
init_p = np.array(
- [math.sqrt(state[0] ** 2 + state[1] ** 2), bestp[4], bestp[5]]).reshape(3, 1)
+ [np.hypot(state[0], state[1]), bestp[4], bestp[5]]).reshape(3, 1)
x, y, yaw, p = planner.optimize_trajectory(target, k0, init_p)
if x is not None:
print("find good path")
result.append(
- [x[-1], y[-1], yaw[-1], float(p[0]), float(p[1]), float(p[2])])
+ [x[-1], y[-1], yaw[-1], float(p[0, 0]), float(p[1, 0]), float(p[2, 0])])
print("finish path generation")
return result
@@ -77,18 +80,28 @@ def generate_path(target_states, k0):
def calc_uniform_polar_states(nxy, nh, d, a_min, a_max, p_min, p_max):
"""
- calc uniform state
- :param nxy: number of position sampling
- :param nh: number of heading sampleing
- :param d: distance of terminal state
- :param a_min: position sampling min angle
- :param a_max: position sampling max angle
- :param p_min: heading sampling min angle
- :param p_max: heading sampling max angle
- :return: states list
- """
+ Parameters
+ ----------
+ nxy :
+ number of position sampling
+ nh :
+ number of heading sampleing
+ d :
+ distance of terminal state
+ a_min :
+ position sampling min angle
+ a_max :
+ position sampling max angle
+ p_min :
+ heading sampling min angle
+ p_max :
+ heading sampling max angle
+
+ Returns
+ -------
+ """
angle_samples = [i / (nxy - 1) for i in range(nxy)]
states = sample_states(angle_samples, a_min, a_max, d, p_max, p_min, nh)
@@ -150,8 +163,8 @@ def calc_lane_states(l_center, l_heading, l_width, v_width, d, nxy):
:param nxy: sampling number
:return: state list
"""
- xc = math.cos(l_heading) * d + math.sin(l_heading) * l_center
- yc = math.sin(l_heading) * d + math.cos(l_heading) * l_center
+ xc = d
+ yc = l_center
states = []
for i in range(nxy):
@@ -295,7 +308,7 @@ def lane_state_sampling_test1():
k0 = 0.0
l_center = 10.0
- l_heading = np.deg2rad(90.0)
+ l_heading = np.deg2rad(0.0)
l_width = 3.0
v_width = 1.0
d = 10
@@ -303,12 +316,15 @@ def lane_state_sampling_test1():
states = calc_lane_states(l_center, l_heading, l_width, v_width, d, nxy)
result = generate_path(states, k0)
+ if show_animation:
+ plt.close("all")
+
for table in result:
- xc, yc, yawc = motion_model.generate_trajectory(
+ x_c, y_c, yaw_c = motion_model.generate_trajectory(
table[3], table[4], table[5], k0)
if show_animation:
- plt.plot(xc, yc, "-r")
+ plt.plot(x_c, y_c, "-r")
if show_animation:
plt.grid(True)
@@ -317,6 +333,7 @@ def lane_state_sampling_test1():
def main():
+ planner.show_animation = show_animation
uniform_terminal_state_sampling_test1()
uniform_terminal_state_sampling_test2()
biased_terminal_state_sampling_test1()
diff --git a/PathPlanning/TimeBasedPathPlanning/BaseClasses.py b/PathPlanning/TimeBasedPathPlanning/BaseClasses.py
new file mode 100644
index 0000000000..745cde45fb
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/BaseClasses.py
@@ -0,0 +1,49 @@
+from abc import ABC, abstractmethod
+from dataclasses import dataclass
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning.Node import NodePath
+import random
+import numpy.random as numpy_random
+
+# Seed randomness for reproducibility
+RANDOM_SEED = 50
+random.seed(RANDOM_SEED)
+numpy_random.seed(RANDOM_SEED)
+
+class SingleAgentPlanner(ABC):
+ """
+ Base class for single agent planners
+ """
+
+ @staticmethod
+ @abstractmethod
+ def plan(grid: Grid, start: Position, goal: Position, verbose: bool = False) -> NodePath:
+ pass
+
+@dataclass
+class StartAndGoal:
+ # Index of this agent
+ index: int
+ # Start position of the robot
+ start: Position
+ # Goal position of the robot
+ goal: Position
+
+ def distance_start_to_goal(self) -> float:
+ return pow(self.goal.x - self.start.x, 2) + pow(self.goal.y - self.start.y, 2)
+
+class MultiAgentPlanner(ABC):
+ """
+ Base class for multi-agent planners
+ """
+
+ @staticmethod
+ @abstractmethod
+ def plan(grid: Grid, start_and_goal_positions: list[StartAndGoal], single_agent_planner_class: SingleAgentPlanner, verbose: bool = False) -> tuple[list[StartAndGoal], list[NodePath]]:
+ """
+ Plan for all agents. Returned paths are in order corresponding to the returned list of `StartAndGoal` objects
+ """
+ pass
\ No newline at end of file
diff --git a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py
new file mode 100644
index 0000000000..ccc2989001
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py
@@ -0,0 +1,370 @@
+"""
+This file implements a grid with a 3d reservation matrix with dimensions for x, y, and time. There
+is also infrastructure to generate dynamic obstacles that move around the grid. The obstacles' paths
+are stored in the reservation matrix on creation.
+"""
+import numpy as np
+import matplotlib.pyplot as plt
+from enum import Enum
+from dataclasses import dataclass
+from PathPlanning.TimeBasedPathPlanning.Node import NodePath, Position
+
+@dataclass
+class Interval:
+ start_time: int
+ end_time: int
+
+class ObstacleArrangement(Enum):
+ # Random obstacle positions and movements
+ RANDOM = 0
+ # Obstacles start in a line in y at center of grid and move side-to-side in x
+ ARRANGEMENT1 = 1
+ # Static obstacle arrangement
+ NARROW_CORRIDOR = 2
+
+"""
+Generates a 2d numpy array with lists for elements.
+"""
+def empty_2d_array_of_lists(x: int, y: int) -> np.ndarray:
+ arr = np.empty((x, y), dtype=object)
+ # assign each element individually - np.full creates references to the same list
+ arr[:] = [[[] for _ in range(y)] for _ in range(x)]
+ return arr
+
+class Grid:
+ # Set in constructor
+ grid_size: np.ndarray
+ reservation_matrix: np.ndarray
+ obstacle_paths: list[list[Position]] = []
+ # Obstacles will never occupy these points. Useful to avoid impossible scenarios
+ obstacle_avoid_points: list[Position] = []
+
+ # Number of time steps in the simulation
+ time_limit: int
+
+ # Logging control
+ verbose = False
+
+ def __init__(
+ self,
+ grid_size: np.ndarray,
+ num_obstacles: int = 40,
+ obstacle_avoid_points: list[Position] = [],
+ obstacle_arrangement: ObstacleArrangement = ObstacleArrangement.RANDOM,
+ time_limit: int = 100,
+ ):
+ self.obstacle_avoid_points = obstacle_avoid_points
+ self.time_limit = time_limit
+ self.grid_size = grid_size
+ self.reservation_matrix = np.zeros((grid_size[0], grid_size[1], self.time_limit))
+
+ if num_obstacles > self.grid_size[0] * self.grid_size[1]:
+ raise Exception("Number of obstacles is greater than grid size!")
+
+ if obstacle_arrangement == ObstacleArrangement.RANDOM:
+ self.obstacle_paths = self.generate_dynamic_obstacles(num_obstacles)
+ elif obstacle_arrangement == ObstacleArrangement.ARRANGEMENT1:
+ self.obstacle_paths = self.obstacle_arrangement_1(num_obstacles)
+ elif obstacle_arrangement == ObstacleArrangement.NARROW_CORRIDOR:
+ self.obstacle_paths = self.generate_narrow_corridor_obstacles(num_obstacles)
+
+ for i, path in enumerate(self.obstacle_paths):
+ obs_idx = i + 1 # avoid using 0 - that indicates free space in the grid
+ for t, position in enumerate(path):
+ # Reserve old & new position at this time step
+ if t > 0:
+ self.reservation_matrix[path[t - 1].x, path[t - 1].y, t] = obs_idx
+ self.reservation_matrix[position.x, position.y, t] = obs_idx
+
+ """
+ Generate dynamic obstacles that move around the grid. Initial positions and movements are random
+ """
+ def generate_dynamic_obstacles(self, obs_count: int) -> list[list[Position]]:
+ obstacle_paths = []
+ for _ in range(0, obs_count):
+ # Sample until a free starting space is found
+ initial_position = self.sample_random_position()
+ while not self.valid_obstacle_position(initial_position, 0):
+ initial_position = self.sample_random_position()
+
+ positions = [initial_position]
+ if self.verbose:
+ print("Obstacle initial position: ", initial_position)
+
+ # Encourage obstacles to mostly stay in place - too much movement leads to chaotic planning scenarios
+ # that are not fun to watch
+ weights = [0.05, 0.05, 0.05, 0.05, 0.8]
+ diffs = [
+ Position(0, 1),
+ Position(0, -1),
+ Position(1, 0),
+ Position(-1, 0),
+ Position(0, 0),
+ ]
+
+ for t in range(1, self.time_limit - 1):
+ sampled_indices = np.random.choice(
+ len(diffs), size=5, replace=False, p=weights
+ )
+ rand_diffs = [diffs[i] for i in sampled_indices]
+
+ valid_position = None
+ for diff in rand_diffs:
+ new_position = positions[-1] + diff
+
+ if not self.valid_obstacle_position(new_position, t):
+ continue
+
+ valid_position = new_position
+ break
+
+ # Impossible situation for obstacle - stay in place
+ # -> this can happen if the oaths of other obstacles this one
+ if valid_position is None:
+ valid_position = positions[-1]
+
+ positions.append(valid_position)
+
+ obstacle_paths.append(positions)
+
+ return obstacle_paths
+
+ """
+ Generate a line of obstacles in y at the center of the grid that move side-to-side in x
+ Bottom half start moving right, top half start moving left. If `obs_count` is less than the length of
+ the grid, only the first `obs_count` obstacles will be generated.
+ """
+ def obstacle_arrangement_1(self, obs_count: int) -> list[list[Position]]:
+ obstacle_paths = []
+ half_grid_x = self.grid_size[0] // 2
+ half_grid_y = self.grid_size[1] // 2
+
+ for y_idx in range(0, min(obs_count, self.grid_size[1])):
+ moving_right = y_idx < half_grid_y
+ position = Position(half_grid_x, y_idx)
+ path = [position]
+
+ for t in range(1, self.time_limit - 1):
+ # sit in place every other time step
+ if t % 2 == 0:
+ path.append(position)
+ continue
+
+ # first check if we should switch direction (at edge of grid)
+ if (moving_right and position.x == self.grid_size[0] - 1) or (
+ not moving_right and position.x == 0
+ ):
+ moving_right = not moving_right
+ # step in direction
+ position = Position(
+ position.x + (1 if moving_right else -1), position.y
+ )
+ path.append(position)
+
+ obstacle_paths.append(path)
+
+ return obstacle_paths
+
+ def generate_narrow_corridor_obstacles(self, obs_count: int) -> list[list[Position]]:
+ obstacle_paths = []
+
+ for y in range(0, self.grid_size[1]):
+ if y > obs_count:
+ break
+
+ if y == self.grid_size[1] // 2:
+ # Skip the middle row
+ continue
+
+ obstacle_path = []
+ x = self.grid_size[0] // 2 # middle of the grid
+ for t in range(0, self.time_limit - 1):
+ obstacle_path.append(Position(x, y))
+
+ obstacle_paths.append(obstacle_path)
+
+ return obstacle_paths
+
+ """
+ Check if the given position is valid at time t
+
+ input:
+ position (Position): (x, y) position
+ t (int): time step
+
+ output:
+ bool: True if position/time combination is valid, False otherwise
+ """
+ def valid_position(self, position: Position, t: int) -> bool:
+ # Check if position is in grid
+ if not self.inside_grid_bounds(position):
+ return False
+
+ # Check if position is not occupied at time t
+ return self.reservation_matrix[position.x, position.y, t] == 0
+
+ """
+ Returns True if the given position is valid at time t and is not in the set of obstacle_avoid_points
+ """
+ def valid_obstacle_position(self, position: Position, t: int) -> bool:
+ return (
+ self.valid_position(position, t)
+ and position not in self.obstacle_avoid_points
+ )
+
+ """
+ Returns True if the given position is within the grid's boundaries
+ """
+ def inside_grid_bounds(self, position: Position) -> bool:
+ return (
+ position.x >= 0
+ and position.x < self.grid_size[0]
+ and position.y >= 0
+ and position.y < self.grid_size[1]
+ )
+
+ """
+ Sample a random position that is within the grid's boundaries
+
+ output:
+ Position: (x, y) position
+ """
+ def sample_random_position(self) -> Position:
+ return Position(
+ np.random.randint(0, self.grid_size[0]),
+ np.random.randint(0, self.grid_size[1]),
+ )
+
+ """
+ Returns a tuple of (x_positions, y_positions) of the obstacles at time t
+ """
+ def get_obstacle_positions_at_time(self, t: int) -> tuple[list[int], list[int]]:
+ x_positions = []
+ y_positions = []
+ for obs_path in self.obstacle_paths:
+ x_positions.append(obs_path[t].x)
+ y_positions.append(obs_path[t].y)
+ return (x_positions, y_positions)
+
+ """
+ Returns safe intervals for each cell.
+ """
+ def get_safe_intervals(self) -> np.ndarray:
+ intervals = empty_2d_array_of_lists(self.grid_size[0], self.grid_size[1])
+ for x in range(intervals.shape[0]):
+ for y in range(intervals.shape[1]):
+ intervals[x, y] = self.get_safe_intervals_at_cell(Position(x, y))
+
+ return intervals
+
+ """
+ Generate the safe intervals for a given cell. The intervals will be in order of start time.
+ ex: Interval (2, 3) will be before Interval (4, 5)
+ """
+ def get_safe_intervals_at_cell(self, cell: Position) -> list[Interval]:
+ vals = self.reservation_matrix[cell.x, cell.y, :]
+ # Find where the array is zero
+ zero_mask = (vals == 0)
+
+ # Identify transitions between zero and nonzero elements
+ diff = np.diff(zero_mask.astype(int))
+
+ # Start indices: where zeros begin (1 after a nonzero)
+ start_indices = np.where(diff == 1)[0] + 1
+
+ # End indices: where zeros stop (just before a nonzero)
+ end_indices = np.where(diff == -1)[0]
+
+ # Handle edge cases if the array starts or ends with zeros
+ if zero_mask[0]: # If the first element is zero, add index 0 to start_indices
+ start_indices = np.insert(start_indices, 0, 0)
+ if zero_mask[-1]: # If the last element is zero, add the last index to end_indices
+ end_indices = np.append(end_indices, len(vals) - 1)
+
+ # Create pairs of (first zero, last zero)
+ intervals = [Interval(int(start), int(end)) for start, end in zip(start_indices, end_indices)]
+
+ # Remove intervals where a cell is only free for one time step. Those intervals not provide enough time to
+ # move into and out of the cell each take 1 time step, and the cell is considered occupied during
+ # both the time step when it is entering the cell, and the time step when it is leaving the cell.
+ intervals = [interval for interval in intervals if interval.start_time != interval.end_time]
+ return intervals
+
+ """
+ Reserve an agent's path in the grid. Raises an exception if the agent's index is 0, or if a position is
+ already reserved by a different agent.
+ """
+ def reserve_path(self, node_path: NodePath, agent_index: int):
+ if agent_index == 0:
+ raise Exception("Agent index cannot be 0")
+
+ for i, node in enumerate(node_path.path):
+ reservation_finish_time = node.time + 1
+ if i < len(node_path.path) - 1:
+ reservation_finish_time = node_path.path[i + 1].time
+
+ self.reserve_position(node.position, agent_index, Interval(node.time, reservation_finish_time))
+
+ """
+ Reserve a position for the provided agent during the provided time interval.
+ Raises an exception if the agent's index is 0, or if the position is already reserved by a different agent during the interval.
+ """
+ def reserve_position(self, position: Position, agent_index: int, interval: Interval):
+ if agent_index == 0:
+ raise Exception("Agent index cannot be 0")
+
+ for t in range(interval.start_time, interval.end_time + 1):
+ current_reserver = self.reservation_matrix[position.x, position.y, t]
+ if current_reserver not in [0, agent_index]:
+ raise Exception(
+ f"Agent {agent_index} tried to reserve a position already reserved by another agent: {position} at time {t}, reserved by {current_reserver}"
+ )
+ self.reservation_matrix[position.x, position.y, t] = agent_index
+
+ """
+ Clears the initial reservation for an agent by clearing reservations at its start position with its index for
+ from time 0 to the time limit.
+ """
+ def clear_initial_reservation(self, position: Position, agent_index: int):
+ for t in range(self.time_limit):
+ if self.reservation_matrix[position.x, position.y, t] == agent_index:
+ self.reservation_matrix[position.x, position.y, t] = 0
+
+show_animation = True
+
+def main():
+ grid = Grid(
+ np.array([11, 11]),
+ num_obstacles=10,
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ )
+
+ if not show_animation:
+ return
+
+ fig = plt.figure(figsize=(8, 7))
+ ax = fig.add_subplot(
+ autoscale_on=False,
+ xlim=(0, grid.grid_size[0] - 1),
+ ylim=(0, grid.grid_size[1] - 1),
+ )
+ ax.set_aspect("equal")
+ ax.grid()
+ ax.set_xticks(np.arange(0, 11, 1))
+ ax.set_yticks(np.arange(0, 11, 1))
+ (obs_points,) = ax.plot([], [], "ro", ms=15)
+
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ "key_release_event", lambda event: [exit(0) if event.key == "escape" else None]
+ )
+
+ for i in range(0, grid.time_limit - 1):
+ obs_positions = grid.get_obstacle_positions_at_time(i)
+ obs_points.set_data(obs_positions[0], obs_positions[1])
+ plt.pause(0.2)
+ plt.show()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/TimeBasedPathPlanning/Node.py b/PathPlanning/TimeBasedPathPlanning/Node.py
new file mode 100644
index 0000000000..728eebb676
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/Node.py
@@ -0,0 +1,99 @@
+from dataclasses import dataclass
+from functools import total_ordering
+import numpy as np
+from typing import Sequence
+
+@dataclass(order=True)
+class Position:
+ x: int
+ y: int
+
+ def as_ndarray(self) -> np.ndarray:
+ return np.array([self.x, self.y])
+
+ def __add__(self, other):
+ if isinstance(other, Position):
+ return Position(self.x + other.x, self.y + other.y)
+ raise NotImplementedError(
+ f"Addition not supported for Position and {type(other)}"
+ )
+
+ def __sub__(self, other):
+ if isinstance(other, Position):
+ return Position(self.x - other.x, self.y - other.y)
+ raise NotImplementedError(
+ f"Subtraction not supported for Position and {type(other)}"
+ )
+
+ def __hash__(self):
+ return hash((self.x, self.y))
+
+@dataclass()
+# Note: Total_ordering is used instead of adding `order=True` to the @dataclass decorator because
+# this class needs to override the __lt__ and __eq__ methods to ignore parent_index. Parent
+# index is just used to track the path found by the algorithm, and has no effect on the quality
+# of a node.
+@total_ordering
+class Node:
+ position: Position
+ time: int
+ heuristic: int
+ parent_index: int
+
+ """
+ This is what is used to drive node expansion. The node with the lowest value is expanded next.
+ This comparison prioritizes the node with the lowest cost-to-come (self.time) + cost-to-go (self.heuristic)
+ """
+ def __lt__(self, other: object):
+ if not isinstance(other, Node):
+ return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}")
+ return (self.time + self.heuristic) < (other.time + other.heuristic)
+
+ """
+ Note: cost and heuristic are not included in eq or hash, since they will always be the same
+ for a given (position, time) pair. Including either cost or heuristic would be redundant.
+ """
+ def __eq__(self, other: object):
+ if not isinstance(other, Node):
+ return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}")
+ return self.position == other.position and self.time == other.time
+
+ def __hash__(self):
+ return hash((self.position, self.time))
+
+class NodePath:
+ path: Sequence[Node]
+ positions_at_time: dict[int, Position]
+ # Number of nodes expanded while finding this path
+ expanded_node_count: int
+
+ def __init__(self, path: Sequence[Node], expanded_node_count: int):
+ self.path = path
+ self.expanded_node_count = expanded_node_count
+
+ self.positions_at_time = {}
+ for i, node in enumerate(path):
+ reservation_finish_time = node.time + 1
+ if i < len(path) - 1:
+ reservation_finish_time = path[i + 1].time
+
+ for t in range(node.time, reservation_finish_time):
+ self.positions_at_time[t] = node.position
+
+ """
+ Get the position of the path at a given time
+ """
+ def get_position(self, time: int) -> Position | None:
+ return self.positions_at_time.get(time)
+
+ """
+ Time stamp of the last node in the path
+ """
+ def goal_reached_time(self) -> int:
+ return self.path[-1].time
+
+ def __repr__(self):
+ repr_string = ""
+ for i, node in enumerate(self.path):
+ repr_string += f"{i}: {node}\n"
+ return repr_string
\ No newline at end of file
diff --git a/PathPlanning/TimeBasedPathPlanning/Plotting.py b/PathPlanning/TimeBasedPathPlanning/Plotting.py
new file mode 100644
index 0000000000..7cd1f615d8
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/Plotting.py
@@ -0,0 +1,135 @@
+import numpy as np
+import matplotlib.pyplot as plt
+from matplotlib.backend_bases import KeyEvent
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import StartAndGoal
+from PathPlanning.TimeBasedPathPlanning.Node import NodePath
+
+'''
+Plot a single agent path.
+'''
+def PlotNodePath(grid: Grid, start: Position, goal: Position, path: NodePath):
+ fig = plt.figure(figsize=(10, 7))
+ ax = fig.add_subplot(
+ autoscale_on=False,
+ xlim=(0, grid.grid_size[0] - 1),
+ ylim=(0, grid.grid_size[1] - 1),
+ )
+ ax.set_aspect("equal")
+ ax.grid()
+ ax.set_xticks(np.arange(0, grid.grid_size[0], 1))
+ ax.set_yticks(np.arange(0, grid.grid_size[1], 1))
+
+ (start_and_goal,) = ax.plot([], [], "mD", ms=15, label="Start and Goal")
+ start_and_goal.set_data([start.x, goal.x], [start.y, goal.y])
+ (obs_points,) = ax.plot([], [], "ro", ms=15, label="Obstacles")
+ (path_points,) = ax.plot([], [], "bo", ms=10, label="Path Found")
+ ax.legend(bbox_to_anchor=(1.05, 1))
+
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ "key_release_event",
+ lambda event: [exit(0) if event.key == "escape" else None]
+ if isinstance(event, KeyEvent) else None
+ )
+
+ for i in range(0, path.goal_reached_time()):
+ obs_positions = grid.get_obstacle_positions_at_time(i)
+ obs_points.set_data(obs_positions[0], obs_positions[1])
+ path_position = path.get_position(i)
+ if not path_position:
+ raise Exception(f"Path position not found for time {i}.")
+
+ path_points.set_data([path_position.x], [path_position.y])
+ plt.pause(0.2)
+ plt.show()
+
+'''
+Plot a series of agent paths.
+'''
+def PlotNodePaths(grid: Grid, start_and_goals: list[StartAndGoal], paths: list[NodePath]):
+ fig = plt.figure(figsize=(10, 7))
+
+ ax = fig.add_subplot(
+ autoscale_on=False,
+ xlim=(0, grid.grid_size[0] - 1),
+ ylim=(0, grid.grid_size[1] - 1),
+ )
+ ax.set_aspect("equal")
+ ax.grid()
+ ax.set_xticks(np.arange(0, grid.grid_size[0], 1))
+ ax.set_yticks(np.arange(0, grid.grid_size[1], 1))
+
+ # Plot start and goal positions for each agent
+ colors = [] # generated randomly in loop
+ markers = ['D', 's', '^', 'o', 'p'] # Different markers for visual distinction
+
+ # Create plots for start and goal positions
+ start_and_goal_plots = []
+ for i, path in enumerate(paths):
+ marker_idx = i % len(markers)
+ agent_id = start_and_goals[i].index
+ start = start_and_goals[i].start
+ goal = start_and_goals[i].goal
+
+ color = np.random.rand(3,)
+ colors.append(color)
+ sg_plot, = ax.plot([], [], markers[marker_idx], c=color, ms=15,
+ label=f"Agent {agent_id} Start/Goal")
+ sg_plot.set_data([start.x, goal.x], [start.y, goal.y])
+ start_and_goal_plots.append(sg_plot)
+
+ # Plot for obstacles
+ (obs_points,) = ax.plot([], [], "ro", ms=15, label="Obstacles")
+
+ # Create plots for each agent's path
+ path_plots = []
+ for i, path in enumerate(paths):
+ agent_id = start_and_goals[i].index
+ path_plot, = ax.plot([], [], "o", c=colors[i], ms=10,
+ label=f"Agent {agent_id} Path")
+ path_plots.append(path_plot)
+
+ ax.legend(bbox_to_anchor=(1.05, 1))
+
+ # For stopping simulation with the esc key
+ plt.gcf().canvas.mpl_connect(
+ "key_release_event",
+ lambda event: [exit(0) if event.key == "escape" else None]
+ if isinstance(event, KeyEvent) else None
+ )
+
+ # Find the maximum time across all paths
+ max_time = max(path.goal_reached_time() for path in paths)
+
+ # Animation loop
+ for i in range(0, max_time + 1):
+ # Update obstacle positions
+ obs_positions = grid.get_obstacle_positions_at_time(i)
+ obs_points.set_data(obs_positions[0], obs_positions[1])
+
+ # Update each agent's position
+ for (j, path) in enumerate(paths):
+ path_positions = []
+ if i <= path.goal_reached_time():
+ res = path.get_position(i)
+ if not res:
+ print(path)
+ print(i)
+ path_position = path.get_position(i)
+ if not path_position:
+ raise Exception(f"Path position not found for time {i}.")
+
+ # Verify position is valid
+ assert not path_position in obs_positions
+ assert not path_position in path_positions
+ path_positions.append(path_position)
+
+ path_plots[j].set_data([path_position.x], [path_position.y])
+
+ plt.pause(0.2)
+
+ plt.show()
\ No newline at end of file
diff --git a/PathPlanning/TimeBasedPathPlanning/PriorityBasedPlanner.py b/PathPlanning/TimeBasedPathPlanning/PriorityBasedPlanner.py
new file mode 100644
index 0000000000..2573965cf6
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/PriorityBasedPlanner.py
@@ -0,0 +1,95 @@
+"""
+Priority Based Planner for multi agent path planning.
+The planner generates an order to plan in, and generates plans for the robots in that order. Each planned
+path is reserved in the grid, and all future plans must avoid that path.
+
+Algorithm outlined in section III of this paper: https://pure.tudelft.nl/ws/portalfiles/portal/67074672/07138650.pdf
+"""
+
+import numpy as np
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ Interval,
+ ObstacleArrangement,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import MultiAgentPlanner, StartAndGoal
+from PathPlanning.TimeBasedPathPlanning.Node import NodePath
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import SingleAgentPlanner
+from PathPlanning.TimeBasedPathPlanning.SafeInterval import SafeIntervalPathPlanner
+from PathPlanning.TimeBasedPathPlanning.Plotting import PlotNodePaths
+import time
+
+class PriorityBasedPlanner(MultiAgentPlanner):
+
+ @staticmethod
+ def plan(grid: Grid, start_and_goals: list[StartAndGoal], single_agent_planner_class: SingleAgentPlanner, verbose: bool = False) -> tuple[list[StartAndGoal], list[NodePath]]:
+ """
+ Generate a path from the start to the goal for each agent in the `start_and_goals` list.
+ Returns the re-ordered StartAndGoal combinations, and a list of path plans. The order of the plans
+ corresponds to the order of the `start_and_goals` list.
+ """
+ print(f"Using single-agent planner: {single_agent_planner_class}")
+
+ # Reserve initial positions
+ for start_and_goal in start_and_goals:
+ grid.reserve_position(start_and_goal.start, start_and_goal.index, Interval(0, 10))
+
+ # Plan in descending order of distance from start to goal
+ start_and_goals = sorted(start_and_goals,
+ key=lambda item: item.distance_start_to_goal(),
+ reverse=True)
+
+ paths = []
+ for start_and_goal in start_and_goals:
+ if verbose:
+ print(f"\nPlanning for agent: {start_and_goal}" )
+
+ grid.clear_initial_reservation(start_and_goal.start, start_and_goal.index)
+ path = single_agent_planner_class.plan(grid, start_and_goal.start, start_and_goal.goal, verbose)
+
+ if path is None:
+ print(f"Failed to find path for {start_and_goal}")
+ return []
+
+ agent_index = start_and_goal.index
+ grid.reserve_path(path, agent_index)
+ paths.append(path)
+
+ return (start_and_goals, paths)
+
+verbose = False
+show_animation = True
+def main():
+ grid_side_length = 21
+
+ start_and_goals = [StartAndGoal(i, Position(1, i), Position(19, 19-i)) for i in range(1, 16)]
+ obstacle_avoid_points = [pos for item in start_and_goals for pos in (item.start, item.goal)]
+
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ num_obstacles=250,
+ obstacle_avoid_points=obstacle_avoid_points,
+ # obstacle_arrangement=ObstacleArrangement.NARROW_CORRIDOR,
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ # obstacle_arrangement=ObstacleArrangement.RANDOM,
+ )
+
+ start_time = time.time()
+ start_and_goals, paths = PriorityBasedPlanner.plan(grid, start_and_goals, SafeIntervalPathPlanner, verbose)
+
+ runtime = time.time() - start_time
+ print(f"\nPlanning took: {runtime:.5f} seconds")
+
+ if verbose:
+ print(f"Paths:")
+ for path in paths:
+ print(f"{path}\n")
+
+ if not show_animation:
+ return
+
+ PlotNodePaths(grid, start_and_goals, paths)
+
+if __name__ == "__main__":
+ main()
\ No newline at end of file
diff --git a/PathPlanning/TimeBasedPathPlanning/SafeInterval.py b/PathPlanning/TimeBasedPathPlanning/SafeInterval.py
new file mode 100644
index 0000000000..446847ac6d
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/SafeInterval.py
@@ -0,0 +1,212 @@
+"""
+Safe interval path planner
+ This script implements a safe-interval path planner for a 2d grid with dynamic obstacles. It is faster than
+ SpaceTime A* because it reduces the number of redundant node expansions by pre-computing regions of adjacent
+ time steps that are safe ("safe intervals") at each position. This allows the algorithm to skip expanding nodes
+ that are in intervals that have already been visited earlier.
+
+ Reference: https://www.cs.cmu.edu/~maxim/files/sipp_icra11.pdf
+"""
+
+import numpy as np
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ Interval,
+ ObstacleArrangement,
+ Position,
+ empty_2d_array_of_lists,
+)
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import SingleAgentPlanner
+from PathPlanning.TimeBasedPathPlanning.Node import Node, NodePath
+from PathPlanning.TimeBasedPathPlanning.Plotting import PlotNodePath
+
+import heapq
+from dataclasses import dataclass
+from functools import total_ordering
+import time
+
+@dataclass()
+# Note: Total_ordering is used instead of adding `order=True` to the @dataclass decorator because
+# this class needs to override the __lt__ and __eq__ methods to ignore parent_index. The Parent
+# index and interval member variables are just used to track the path found by the algorithm,
+# and has no effect on the quality of a node.
+@total_ordering
+class SIPPNode(Node):
+ interval: Interval
+
+@dataclass
+class EntryTimeAndInterval:
+ entry_time: int
+ interval: Interval
+
+class SafeIntervalPathPlanner(SingleAgentPlanner):
+
+ """
+ Generate a plan given the loaded problem statement. Raises an exception if it fails to find a path.
+ Arguments:
+ verbose (bool): set to True to print debug information
+ """
+ @staticmethod
+ def plan(grid: Grid, start: Position, goal: Position, verbose: bool = False) -> NodePath:
+
+ safe_intervals = grid.get_safe_intervals()
+
+ open_set: list[SIPPNode] = []
+ first_node_interval = safe_intervals[start.x, start.y][0]
+ heapq.heappush(
+ open_set, SIPPNode(start, 0, SafeIntervalPathPlanner.calculate_heuristic(start, goal), -1, first_node_interval)
+ )
+
+ expanded_list: list[SIPPNode] = []
+ visited_intervals = empty_2d_array_of_lists(grid.grid_size[0], grid.grid_size[1])
+ while open_set:
+ expanded_node: SIPPNode = heapq.heappop(open_set)
+ if verbose:
+ print("Expanded node:", expanded_node)
+
+ if expanded_node.time + 1 >= grid.time_limit:
+ if verbose:
+ print(f"\tSkipping node that is past time limit: {expanded_node}")
+ continue
+
+ if expanded_node.position == goal:
+ if verbose:
+ print(f"Found path to goal after {len(expanded_list)} expansions")
+
+ path = []
+ path_walker: SIPPNode = expanded_node
+ while True:
+ path.append(path_walker)
+ if path_walker.parent_index == -1:
+ break
+ path_walker = expanded_list[path_walker.parent_index]
+
+ # reverse path so it goes start -> goal
+ path.reverse()
+ return NodePath(path, len(expanded_list))
+
+ expanded_idx = len(expanded_list)
+ expanded_list.append(expanded_node)
+ entry_time_and_node = EntryTimeAndInterval(expanded_node.time, expanded_node.interval)
+ add_entry_to_visited_intervals_array(entry_time_and_node, visited_intervals, expanded_node)
+
+ for child in SafeIntervalPathPlanner.generate_successors(grid, goal, expanded_node, expanded_idx, safe_intervals, visited_intervals):
+ heapq.heappush(open_set, child)
+
+ raise Exception("No path found")
+
+ """
+ Generate list of possible successors of the provided `parent_node` that are worth expanding
+ """
+ @staticmethod
+ def generate_successors(
+ grid: Grid, goal: Position, parent_node: SIPPNode, parent_node_idx: int, intervals: np.ndarray, visited_intervals: np.ndarray
+ ) -> list[SIPPNode]:
+ new_nodes = []
+ diffs = [
+ Position(0, 0),
+ Position(1, 0),
+ Position(-1, 0),
+ Position(0, 1),
+ Position(0, -1),
+ ]
+ for diff in diffs:
+ new_pos = parent_node.position + diff
+ if not grid.inside_grid_bounds(new_pos):
+ continue
+
+ current_interval = parent_node.interval
+
+ new_cell_intervals: list[Interval] = intervals[new_pos.x, new_pos.y]
+ for interval in new_cell_intervals:
+ # if interval starts after current ends, break
+ # assumption: intervals are sorted by start time, so all future intervals will hit this condition as well
+ if interval.start_time > current_interval.end_time:
+ break
+
+ # if interval ends before current starts, skip
+ if interval.end_time < current_interval.start_time:
+ continue
+
+ # if we have already expanded a node in this interval with a <= starting time, skip
+ better_node_expanded = False
+ for visited in visited_intervals[new_pos.x, new_pos.y]:
+ if interval == visited.interval and visited.entry_time <= parent_node.time + 1:
+ better_node_expanded = True
+ break
+ if better_node_expanded:
+ continue
+
+ # We know there is a node worth expanding. Generate successor at the earliest possible time the
+ # new interval can be entered
+ for possible_t in range(max(parent_node.time + 1, interval.start_time), min(current_interval.end_time, interval.end_time)):
+ if grid.valid_position(new_pos, possible_t):
+ new_nodes.append(SIPPNode(
+ new_pos,
+ # entry is max of interval start and parent node time + 1 (get there as soon as possible)
+ max(interval.start_time, parent_node.time + 1),
+ SafeIntervalPathPlanner.calculate_heuristic(new_pos, goal),
+ parent_node_idx,
+ interval,
+ ))
+ # break because all t's after this will make nodes with a higher cost, the same heuristic, and are in the same interval
+ break
+
+ return new_nodes
+
+ """
+ Calculate the heuristic for a given position - Manhattan distance to the goal
+ """
+ @staticmethod
+ def calculate_heuristic(position: Position, goal: Position) -> int:
+ diff = goal - position
+ return abs(diff.x) + abs(diff.y)
+
+
+"""
+Adds a new entry to the visited intervals array. If the entry is already present, the entry time is updated if the new
+entry time is better. Otherwise, the entry is added to `visited_intervals` at the position of `expanded_node`.
+"""
+def add_entry_to_visited_intervals_array(entry_time_and_interval: EntryTimeAndInterval, visited_intervals: np.ndarray, expanded_node: SIPPNode):
+ # if entry is present, update entry time if better
+ for existing_entry_and_interval in visited_intervals[expanded_node.position.x, expanded_node.position.y]:
+ if existing_entry_and_interval.interval == entry_time_and_interval.interval:
+ existing_entry_and_interval.entry_time = min(existing_entry_and_interval.entry_time, entry_time_and_interval.entry_time)
+
+ # Otherwise, append
+ visited_intervals[expanded_node.position.x, expanded_node.position.y].append(entry_time_and_interval)
+
+
+show_animation = True
+verbose = False
+
+def main():
+ start = Position(1, 18)
+ goal = Position(19, 19)
+ grid_side_length = 21
+
+ start_time = time.time()
+
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ num_obstacles=250,
+ obstacle_avoid_points=[start, goal],
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ # obstacle_arrangement=ObstacleArrangement.RANDOM,
+ )
+
+ path = SafeIntervalPathPlanner.plan(grid, start, goal, verbose)
+ runtime = time.time() - start_time
+ print(f"Planning took: {runtime:.5f} seconds")
+
+ if verbose:
+ print(f"Path: {path}")
+
+ if not show_animation:
+ return
+
+ PlotNodePath(grid, start, goal, path)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py
new file mode 100644
index 0000000000..b85569f5dc
--- /dev/null
+++ b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py
@@ -0,0 +1,139 @@
+"""
+Space-time A* Algorithm
+ This script demonstrates the Space-time A* algorithm for path planning in a grid world with moving obstacles.
+ This algorithm is different from normal 2D A* in one key way - the cost (often notated as g(n)) is
+ the number of time steps it took to get to a given node, instead of the number of cells it has
+ traversed. This ensures the path is time-optimal, while respecting any dynamic obstacles in the environment.
+
+ Reference: https://www.davidsilver.uk/wp-content/uploads/2020/03/coop-path-AIWisdom.pdf
+"""
+
+import numpy as np
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ ObstacleArrangement,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning.Node import Node, NodePath
+import heapq
+from collections.abc import Generator
+import time
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import SingleAgentPlanner
+from PathPlanning.TimeBasedPathPlanning.Plotting import PlotNodePath
+
+class SpaceTimeAStar(SingleAgentPlanner):
+
+ @staticmethod
+ def plan(grid: Grid, start: Position, goal: Position, verbose: bool = False) -> NodePath:
+ open_set: list[Node] = []
+ heapq.heappush(
+ open_set, Node(start, 0, SpaceTimeAStar.calculate_heuristic(start, goal), -1)
+ )
+
+ expanded_list: list[Node] = []
+ expanded_set: set[Node] = set()
+ while open_set:
+ expanded_node: Node = heapq.heappop(open_set)
+ if verbose:
+ print("Expanded node:", expanded_node)
+
+ if expanded_node.time + 1 >= grid.time_limit:
+ if verbose:
+ print(f"\tSkipping node that is past time limit: {expanded_node}")
+ continue
+
+ if expanded_node.position == goal:
+ if verbose:
+ print(f"Found path to goal after {len(expanded_list)} expansions")
+
+ path = []
+ path_walker: Node = expanded_node
+ while True:
+ path.append(path_walker)
+ if path_walker.parent_index == -1:
+ break
+ path_walker = expanded_list[path_walker.parent_index]
+
+ # reverse path so it goes start -> goal
+ path.reverse()
+ return NodePath(path, len(expanded_set))
+
+ expanded_idx = len(expanded_list)
+ expanded_list.append(expanded_node)
+ expanded_set.add(expanded_node)
+
+ for child in SpaceTimeAStar.generate_successors(grid, goal, expanded_node, expanded_idx, verbose, expanded_set):
+ heapq.heappush(open_set, child)
+
+ raise Exception("No path found")
+
+ """
+ Generate possible successors of the provided `parent_node`
+ """
+ @staticmethod
+ def generate_successors(
+ grid: Grid, goal: Position, parent_node: Node, parent_node_idx: int, verbose: bool, expanded_set: set[Node]
+ ) -> Generator[Node, None, None]:
+ diffs = [
+ Position(0, 0),
+ Position(1, 0),
+ Position(-1, 0),
+ Position(0, 1),
+ Position(0, -1),
+ ]
+ for diff in diffs:
+ new_pos = parent_node.position + diff
+ new_node = Node(
+ new_pos,
+ parent_node.time + 1,
+ SpaceTimeAStar.calculate_heuristic(new_pos, goal),
+ parent_node_idx,
+ )
+
+ if new_node in expanded_set:
+ continue
+
+ # Check if the new node is valid for the next 2 time steps - one step to enter, and another to leave
+ if all([grid.valid_position(new_pos, parent_node.time + dt) for dt in [1, 2]]):
+ if verbose:
+ print("\tNew successor node: ", new_node)
+ yield new_node
+
+ @staticmethod
+ def calculate_heuristic(position: Position, goal: Position) -> int:
+ diff = goal - position
+ return abs(diff.x) + abs(diff.y)
+
+
+show_animation = True
+verbose = False
+
+def main():
+ start = Position(1, 5)
+ goal = Position(19, 19)
+ grid_side_length = 21
+
+ start_time = time.time()
+
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ num_obstacles=40,
+ obstacle_avoid_points=[start, goal],
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ )
+
+ path = SpaceTimeAStar.plan(grid, start, goal, verbose)
+
+ runtime = time.time() - start_time
+ print(f"Planning took: {runtime:.5f} seconds")
+
+ if verbose:
+ print(f"Path: {path}")
+
+ if not show_animation:
+ return
+
+ PlotNodePath(grid, start, goal, path)
+
+if __name__ == "__main__":
+ main()
diff --git a/PathPlanning/TimeBasedPathPlanning/__init__.py b/PathPlanning/TimeBasedPathPlanning/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/VisibilityRoadMap/__init__.py b/PathPlanning/VisibilityRoadMap/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/VisibilityRoadMap/geometry.py b/PathPlanning/VisibilityRoadMap/geometry.py
new file mode 100644
index 0000000000..b15cdb8a43
--- /dev/null
+++ b/PathPlanning/VisibilityRoadMap/geometry.py
@@ -0,0 +1,44 @@
+class Geometry:
+
+ class Point:
+ def __init__(self, x, y):
+ self.x = x
+ self.y = y
+
+ @staticmethod
+ def is_seg_intersect(p1, q1, p2, q2):
+
+ def on_segment(p, q, r):
+ if ((q.x <= max(p.x, r.x)) and (q.x >= min(p.x, r.x)) and
+ (q.y <= max(p.y, r.y)) and (q.y >= min(p.y, r.y))):
+ return True
+ return False
+
+ def orientation(p, q, r):
+ val = (float(q.y - p.y) * (r.x - q.x)) - (
+ float(q.x - p.x) * (r.y - q.y))
+ if val > 0:
+ return 1
+ if val < 0:
+ return 2
+ return 0
+
+ # Find the 4 orientations required for
+ # the general and special cases
+ o1 = orientation(p1, q1, p2)
+ o2 = orientation(p1, q1, q2)
+ o3 = orientation(p2, q2, p1)
+ o4 = orientation(p2, q2, q1)
+
+ if (o1 != o2) and (o3 != o4):
+ return True
+ if (o1 == 0) and on_segment(p1, p2, q1):
+ return True
+ if (o2 == 0) and on_segment(p1, q2, q1):
+ return True
+ if (o3 == 0) and on_segment(p2, p1, q2):
+ return True
+ if (o4 == 0) and on_segment(p2, q1, q2):
+ return True
+
+ return False
diff --git a/PathPlanning/VisibilityRoadMap/visibility_road_map.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py
new file mode 100644
index 0000000000..5f7ffadd16
--- /dev/null
+++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py
@@ -0,0 +1,222 @@
+"""
+
+Visibility Road Map Planner
+
+author: Atsushi Sakai (@Atsushi_twi)
+
+"""
+
+import sys
+import math
+import numpy as np
+import matplotlib.pyplot as plt
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
+
+from VisibilityRoadMap.geometry import Geometry
+from VoronoiRoadMap.dijkstra_search import DijkstraSearch
+
+show_animation = True
+
+
+class VisibilityRoadMap:
+
+ def __init__(self, expand_distance, do_plot=False):
+ self.expand_distance = expand_distance
+ self.do_plot = do_plot
+
+ def planning(self, start_x, start_y, goal_x, goal_y, obstacles):
+
+ nodes = self.generate_visibility_nodes(start_x, start_y,
+ goal_x, goal_y, obstacles)
+
+ road_map_info = self.generate_road_map_info(nodes, obstacles)
+
+ if self.do_plot:
+ self.plot_road_map(nodes, road_map_info)
+ plt.pause(1.0)
+
+ rx, ry = DijkstraSearch(show_animation).search(
+ start_x, start_y,
+ goal_x, goal_y,
+ [node.x for node in nodes],
+ [node.y for node in nodes],
+ road_map_info
+ )
+
+ return rx, ry
+
+ def generate_visibility_nodes(self, start_x, start_y, goal_x, goal_y,
+ obstacles):
+
+ # add start and goal as nodes
+ nodes = [DijkstraSearch.Node(start_x, start_y),
+ DijkstraSearch.Node(goal_x, goal_y, 0, None)]
+
+ # add vertexes in configuration space as nodes
+ for obstacle in obstacles:
+
+ cvx_list, cvy_list = self.calc_vertexes_in_configuration_space(
+ obstacle.x_list, obstacle.y_list)
+
+ for (vx, vy) in zip(cvx_list, cvy_list):
+ nodes.append(DijkstraSearch.Node(vx, vy))
+
+ if self.do_plot:
+ for node in nodes:
+ plt.plot(node.x, node.y, "xr")
+
+ return nodes
+
+ def calc_vertexes_in_configuration_space(self, x_list, y_list):
+ x_list = x_list[0:-1]
+ y_list = y_list[0:-1]
+ cvx_list, cvy_list = [], []
+
+ n_data = len(x_list)
+
+ for index in range(n_data):
+ offset_x, offset_y = self.calc_offset_xy(
+ x_list[index - 1], y_list[index - 1],
+ x_list[index], y_list[index],
+ x_list[(index + 1) % n_data], y_list[(index + 1) % n_data],
+ )
+ cvx_list.append(offset_x)
+ cvy_list.append(offset_y)
+
+ return cvx_list, cvy_list
+
+ def generate_road_map_info(self, nodes, obstacles):
+
+ road_map_info_list = []
+
+ for target_node in nodes:
+ road_map_info = []
+ for node_id, node in enumerate(nodes):
+ if np.hypot(target_node.x - node.x,
+ target_node.y - node.y) <= 0.1:
+ continue
+
+ is_valid = True
+ for obstacle in obstacles:
+ if not self.is_edge_valid(target_node, node, obstacle):
+ is_valid = False
+ break
+ if is_valid:
+ road_map_info.append(node_id)
+
+ road_map_info_list.append(road_map_info)
+
+ return road_map_info_list
+
+ @staticmethod
+ def is_edge_valid(target_node, node, obstacle):
+
+ for i in range(len(obstacle.x_list) - 1):
+ p1 = Geometry.Point(target_node.x, target_node.y)
+ p2 = Geometry.Point(node.x, node.y)
+ p3 = Geometry.Point(obstacle.x_list[i], obstacle.y_list[i])
+ p4 = Geometry.Point(obstacle.x_list[i + 1], obstacle.y_list[i + 1])
+
+ if Geometry.is_seg_intersect(p1, p2, p3, p4):
+ return False
+
+ return True
+
+ def calc_offset_xy(self, px, py, x, y, nx, ny):
+ p_vec = math.atan2(y - py, x - px)
+ n_vec = math.atan2(ny - y, nx - x)
+ offset_vec = math.atan2(math.sin(p_vec) + math.sin(n_vec),
+ math.cos(p_vec) + math.cos(
+ n_vec)) + math.pi / 2.0
+ offset_x = x + self.expand_distance * math.cos(offset_vec)
+ offset_y = y + self.expand_distance * math.sin(offset_vec)
+ return offset_x, offset_y
+
+ @staticmethod
+ def plot_road_map(nodes, road_map_info_list):
+ for i, node in enumerate(nodes):
+ for index in road_map_info_list[i]:
+ plt.plot([node.x, nodes[index].x],
+ [node.y, nodes[index].y], "-b")
+
+
+class ObstaclePolygon:
+
+ def __init__(self, x_list, y_list):
+ self.x_list = x_list
+ self.y_list = y_list
+
+ self.close_polygon()
+ self.make_clockwise()
+
+ def make_clockwise(self):
+ if not self.is_clockwise():
+ self.x_list = list(reversed(self.x_list))
+ self.y_list = list(reversed(self.y_list))
+
+ def is_clockwise(self):
+ n_data = len(self.x_list)
+ eval_sum = sum([(self.x_list[i + 1] - self.x_list[i]) *
+ (self.y_list[i + 1] + self.y_list[i])
+ for i in range(n_data - 1)])
+ eval_sum += (self.x_list[0] - self.x_list[n_data - 1]) * \
+ (self.y_list[0] + self.y_list[n_data - 1])
+ return eval_sum >= 0
+
+ def close_polygon(self):
+ is_x_same = self.x_list[0] == self.x_list[-1]
+ is_y_same = self.y_list[0] == self.y_list[-1]
+ if is_x_same and is_y_same:
+ return # no need to close
+
+ self.x_list.append(self.x_list[0])
+ self.y_list.append(self.y_list[0])
+
+ def plot(self):
+ plt.plot(self.x_list, self.y_list, "-k")
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # start and goal position
+ sx, sy = 10.0, 10.0 # [m]
+ gx, gy = 50.0, 50.0 # [m]
+
+ expand_distance = 5.0 # [m]
+
+ obstacles = [
+ ObstaclePolygon(
+ [20.0, 30.0, 15.0],
+ [20.0, 20.0, 30.0],
+ ),
+ ObstaclePolygon(
+ [40.0, 45.0, 50.0, 40.0],
+ [50.0, 40.0, 20.0, 40.0],
+ ),
+ ObstaclePolygon(
+ [20.0, 30.0, 30.0, 20.0],
+ [40.0, 45.0, 60.0, 50.0],
+ )
+ ]
+
+ if show_animation: # pragma: no cover
+ plt.plot(sx, sy, "or")
+ plt.plot(gx, gy, "ob")
+ for ob in obstacles:
+ ob.plot()
+ plt.axis("equal")
+ plt.pause(1.0)
+
+ rx, ry = VisibilityRoadMap(expand_distance, do_plot=show_animation)\
+ .planning(sx, sy, gx, gy, obstacles)
+
+ if show_animation: # pragma: no cover
+ plt.plot(rx, ry, "-r")
+ plt.pause(0.1)
+ plt.show()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathPlanning/VoronoiRoadMap/__init__.py b/PathPlanning/VoronoiRoadMap/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py
new file mode 100644
index 0000000000..503ccc342e
--- /dev/null
+++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py
@@ -0,0 +1,140 @@
+"""
+
+Dijkstra Search library
+
+author: Atsushi Sakai (@Atsushi_twi)
+
+"""
+
+import matplotlib.pyplot as plt
+import math
+import numpy as np
+
+
+class DijkstraSearch:
+ class Node:
+ """
+ Node class for dijkstra search
+ """
+
+ def __init__(self, x, y, cost=None, parent=None, edge_ids=None):
+ self.x = x
+ self.y = y
+ self.cost = cost
+ self.parent = parent
+ self.edge_ids = edge_ids
+
+ def __str__(self):
+ return str(self.x) + "," + str(self.y) + "," + str(
+ self.cost) + "," + str(self.parent)
+
+ def __init__(self, show_animation):
+ self.show_animation = show_animation
+
+ def search(self, sx, sy, gx, gy, node_x, node_y, edge_ids_list):
+ """
+ Search shortest path
+
+ s_x: start x positions [m]
+ s_y: start y positions [m]
+ gx: goal x position [m]
+ gx: goal x position [m]
+ node_x: node x position
+ node_y: node y position
+ edge_ids_list: edge_list each item includes a list of edge ids
+ """
+
+ start_node = self.Node(sx, sy, 0.0, -1)
+ goal_node = self.Node(gx, gy, 0.0, -1)
+ current_node = None
+
+ open_set, close_set = dict(), dict()
+ open_set[self.find_id(node_x, node_y, start_node)] = start_node
+
+ while True:
+ if self.has_node_in_set(close_set, goal_node):
+ print("goal is found!")
+ goal_node.parent = current_node.parent
+ goal_node.cost = current_node.cost
+ break
+ elif not open_set:
+ print("Cannot find path")
+ break
+
+ current_id = min(open_set, key=lambda o: open_set[o].cost)
+ current_node = open_set[current_id]
+
+ # show graph
+ if self.show_animation and len(
+ close_set.keys()) % 2 == 0: # pragma: no cover
+ plt.plot(current_node.x, current_node.y, "xg")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.pause(0.1)
+
+ # Remove the item from the open set
+ del open_set[current_id]
+ # Add it to the closed set
+ close_set[current_id] = current_node
+
+ # expand search grid based on motion model
+ for i in range(len(edge_ids_list[current_id])):
+ n_id = edge_ids_list[current_id][i]
+ dx = node_x[n_id] - current_node.x
+ dy = node_y[n_id] - current_node.y
+ d = math.hypot(dx, dy)
+ node = self.Node(node_x[n_id], node_y[n_id],
+ current_node.cost + d, current_id)
+
+ if n_id in close_set:
+ continue
+ # Otherwise if it is already in the open set
+ if n_id in open_set:
+ if open_set[n_id].cost > node.cost:
+ open_set[n_id] = node
+ else:
+ open_set[n_id] = node
+
+ # generate final course
+ rx, ry = self.generate_final_path(close_set, goal_node)
+
+ return rx, ry
+
+ @staticmethod
+ def generate_final_path(close_set, goal_node):
+ rx, ry = [goal_node.x], [goal_node.y]
+ parent = goal_node.parent
+ while parent != -1:
+ n = close_set[parent]
+ rx.append(n.x)
+ ry.append(n.y)
+ parent = n.parent
+ rx, ry = rx[::-1], ry[::-1] # reverse it
+ return rx, ry
+
+ def has_node_in_set(self, target_set, node):
+ for key in target_set:
+ if self.is_same_node(target_set[key], node):
+ return True
+ return False
+
+ def find_id(self, node_x_list, node_y_list, target_node):
+ for i, _ in enumerate(node_x_list):
+ if self.is_same_node_with_xy(node_x_list[i], node_y_list[i],
+ target_node):
+ return i
+ return None
+
+ @staticmethod
+ def is_same_node_with_xy(node_x, node_y, node_b):
+ dist = np.hypot(node_x - node_b.x,
+ node_y - node_b.y)
+ return dist <= 0.1
+
+ @staticmethod
+ def is_same_node(node_a, node_b):
+ dist = np.hypot(node_a.x - node_b.x,
+ node_a.y - node_b.y)
+ return dist <= 0.1
diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py
index 3ac02993b7..a27e1b6928 100644
--- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py
+++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py
@@ -8,251 +8,128 @@
import math
import numpy as np
-import scipy.spatial
import matplotlib.pyplot as plt
+from scipy.spatial import cKDTree, Voronoi
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent))
-# parameter
-N_KNN = 10 # number of edge from one sampled point
-MAX_EDGE_LEN = 30.0 # [m] Maximum edge length
+from VoronoiRoadMap.dijkstra_search import DijkstraSearch
show_animation = True
-class Node:
- """
- Node class for dijkstra search
- """
+class VoronoiRoadMapPlanner:
- def __init__(self, x, y, cost, pind):
- self.x = x
- self.y = y
- self.cost = cost
- self.pind = pind
+ def __init__(self):
+ # parameter
+ self.N_KNN = 10 # number of edge from one sampled point
+ self.MAX_EDGE_LEN = 30.0 # [m] Maximum edge length
- def __str__(self):
- return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
+ def planning(self, sx, sy, gx, gy, ox, oy, robot_radius):
+ obstacle_tree = cKDTree(np.vstack((ox, oy)).T)
+ sample_x, sample_y = self.voronoi_sampling(sx, sy, gx, gy, ox, oy)
+ if show_animation: # pragma: no cover
+ plt.plot(sample_x, sample_y, ".b")
-class KDTree:
- """
- Nearest neighbor search class with KDTree
- """
+ road_map_info = self.generate_road_map_info(
+ sample_x, sample_y, robot_radius, obstacle_tree)
- def __init__(self, data):
- # store kd-tree
- self.tree = scipy.spatial.cKDTree(data)
+ rx, ry = DijkstraSearch(show_animation).search(sx, sy, gx, gy,
+ sample_x, sample_y,
+ road_map_info)
+ return rx, ry
- def search(self, inp, k=1):
- """
- Search NN
-
- inp: input data, single frame or multi frame
-
- """
-
- if len(inp.shape) >= 2: # multi input
- index = []
- dist = []
-
- for i in inp.T:
- idist, iindex = self.tree.query(i, k=k)
- index.append(iindex)
- dist.append(idist)
-
- return index, dist
-
- dist, index = self.tree.query(inp, k=k)
- return index, dist
-
- def search_in_distance(self, inp, r):
- """
- find points with in a distance r
- """
-
- index = self.tree.query_ball_point(inp, r)
- return index
-
-
-def VRM_planning(sx, sy, gx, gy, ox, oy, rr):
-
- obkdtree = KDTree(np.vstack((ox, oy)).T)
-
- sample_x, sample_y = sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree)
- if show_animation: # pragma: no cover
- plt.plot(sample_x, sample_y, ".b")
-
- road_map = generate_roadmap(sample_x, sample_y, rr, obkdtree)
-
- rx, ry = dijkstra_planning(
- sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y)
+ def is_collision(self, sx, sy, gx, gy, rr, obstacle_kd_tree):
+ x = sx
+ y = sy
+ dx = gx - sx
+ dy = gy - sy
+ yaw = math.atan2(gy - sy, gx - sx)
+ d = math.hypot(dx, dy)
- return rx, ry
+ if d >= self.MAX_EDGE_LEN:
+ return True
+ D = rr
+ n_step = round(d / D)
-def is_collision(sx, sy, gx, gy, rr, okdtree):
- x = sx
- y = sy
- dx = gx - sx
- dy = gy - sy
- yaw = math.atan2(gy - sy, gx - sx)
- d = math.sqrt(dx**2 + dy**2)
+ for i in range(n_step):
+ dist, _ = obstacle_kd_tree.query([x, y])
+ if dist <= rr:
+ return True # collision
+ x += D * math.cos(yaw)
+ y += D * math.sin(yaw)
- if d >= MAX_EDGE_LEN:
- return True
-
- D = rr
- nstep = round(d / D)
-
- for i in range(nstep):
- idxs, dist = okdtree.search(np.array([x, y]).reshape(2, 1))
- if dist[0] <= rr:
+ # goal point check
+ dist, _ = obstacle_kd_tree.query([gx, gy])
+ if dist <= rr:
return True # collision
- x += D * math.cos(yaw)
- y += D * math.sin(yaw)
-
- # goal point check
- idxs, dist = okdtree.search(np.array([gx, gy]).reshape(2, 1))
- if dist[0] <= rr:
- return True # collision
-
- return False # OK
-
-
-def generate_roadmap(sample_x, sample_y, rr, obkdtree):
- """
- Road map generation
-
- sample_x: [m] x positions of sampled points
- sample_y: [m] y positions of sampled points
- rr: Robot Radius[m]
- obkdtree: KDTree object of obstacles
- """
-
- road_map = []
- nsample = len(sample_x)
- skdtree = KDTree(np.vstack((sample_x, sample_y)).T)
-
- for (i, ix, iy) in zip(range(nsample), sample_x, sample_y):
-
- index, dists = skdtree.search(
- np.array([ix, iy]).reshape(2, 1), k=nsample)
-
- inds = index[0]
- edge_id = []
- # print(index)
-
- for ii in range(1, len(inds)):
- nx = sample_x[inds[ii]]
- ny = sample_y[inds[ii]]
- if not is_collision(ix, iy, nx, ny, rr, obkdtree):
- edge_id.append(inds[ii])
+ return False # OK
- if len(edge_id) >= N_KNN:
- break
-
- road_map.append(edge_id)
-
- # plot_road_map(road_map, sample_x, sample_y)
-
- return road_map
-
-
-def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y):
- """
- gx: goal x position [m]
- gx: goal x position [m]
- ox: x position list of Obstacles [m]
- oy: y position list of Obstacles [m]
- reso: grid resolution [m]
- rr: robot radius[m]
- """
-
- nstart = Node(sx, sy, 0.0, -1)
- ngoal = Node(gx, gy, 0.0, -1)
-
- openset, closedset = dict(), dict()
- openset[len(road_map) - 2] = nstart
+ def generate_road_map_info(self, node_x, node_y, rr, obstacle_tree):
+ """
+ Road map generation
- while True:
- if not openset:
- print("Cannot find path")
- break
+ node_x: [m] x positions of sampled points
+ node_y: [m] y positions of sampled points
+ rr: Robot Radius[m]
+ obstacle_tree: KDTree object of obstacles
+ """
- c_id = min(openset, key=lambda o: openset[o].cost)
- current = openset[c_id]
+ road_map = []
+ n_sample = len(node_x)
+ node_tree = cKDTree(np.vstack((node_x, node_y)).T)
- # show graph
- if show_animation and len(closedset.keys()) % 2 == 0: # pragma: no cover
- plt.plot(current.x, current.y, "xg")
- plt.pause(0.001)
+ for (i, ix, iy) in zip(range(n_sample), node_x, node_y):
- if c_id == (len(road_map) - 1):
- print("goal is found!")
- ngoal.pind = current.pind
- ngoal.cost = current.cost
- break
+ dists, indexes = node_tree.query([ix, iy], k=n_sample)
- # Remove the item from the open set
- del openset[c_id]
- # Add it to the closed set
- closedset[c_id] = current
+ edge_id = []
- # expand search grid based on motion model
- for i in range(len(road_map[c_id])):
- n_id = road_map[c_id][i]
- dx = sample_x[n_id] - current.x
- dy = sample_y[n_id] - current.y
- d = math.sqrt(dx**2 + dy**2)
- node = Node(sample_x[n_id], sample_y[n_id],
- current.cost + d, c_id)
+ for ii in range(1, len(indexes)):
+ nx = node_x[indexes[ii]]
+ ny = node_y[indexes[ii]]
- if n_id in closedset:
- continue
- # Otherwise if it is already in the open set
- if n_id in openset:
- if openset[n_id].cost > node.cost:
- openset[n_id].cost = node.cost
- openset[n_id].pind = c_id
- else:
- openset[n_id] = node
+ if not self.is_collision(ix, iy, nx, ny, rr, obstacle_tree):
+ edge_id.append(indexes[ii])
- # generate final course
- rx, ry = [ngoal.x], [ngoal.y]
- pind = ngoal.pind
- while pind != -1:
- n = closedset[pind]
- rx.append(n.x)
- ry.append(n.y)
- pind = n.pind
+ if len(edge_id) >= self.N_KNN:
+ break
- return rx, ry
+ road_map.append(edge_id)
+ # plot_road_map(road_map, sample_x, sample_y)
-def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover
+ return road_map
- for i, _ in enumerate(road_map):
- for ii in range(len(road_map[i])):
- ind = road_map[i][ii]
+ @staticmethod
+ def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover
- plt.plot([sample_x[i], sample_x[ind]],
- [sample_y[i], sample_y[ind]], "-k")
+ for i, _ in enumerate(road_map):
+ for ii in range(len(road_map[i])):
+ ind = road_map[i][ii]
+ plt.plot([sample_x[i], sample_x[ind]],
+ [sample_y[i], sample_y[ind]], "-k")
-def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree):
- oxy = np.vstack((ox, oy)).T
+ @staticmethod
+ def voronoi_sampling(sx, sy, gx, gy, ox, oy):
+ oxy = np.vstack((ox, oy)).T
- # generate voronoi point
- vor = scipy.spatial.Voronoi(oxy)
- sample_x = [ix for [ix, iy] in vor.vertices]
- sample_y = [iy for [ix, iy] in vor.vertices]
+ # generate voronoi point
+ vor = Voronoi(oxy)
+ sample_x = [ix for [ix, _] in vor.vertices]
+ sample_y = [iy for [_, iy] in vor.vertices]
- sample_x.append(sx)
- sample_y.append(sy)
- sample_x.append(gx)
- sample_y.append(gy)
+ sample_x.append(sx)
+ sample_y.append(sy)
+ sample_x.append(gx)
+ sample_y.append(gy)
- return sample_x, sample_y
+ return sample_x, sample_y
def main():
@@ -269,20 +146,20 @@ def main():
oy = []
for i in range(60):
- ox.append(i)
+ ox.append(float(i))
oy.append(0.0)
for i in range(60):
ox.append(60.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(61):
- ox.append(i)
+ ox.append(float(i))
oy.append(60.0)
for i in range(61):
ox.append(0.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(40):
ox.append(20.0)
- oy.append(i)
+ oy.append(float(i))
for i in range(40):
ox.append(40.0)
oy.append(60.0 - i)
@@ -294,12 +171,14 @@ def main():
plt.grid(True)
plt.axis("equal")
- rx, ry = VRM_planning(sx, sy, gx, gy, ox, oy, robot_size)
+ rx, ry = VoronoiRoadMapPlanner().planning(sx, sy, gx, gy, ox, oy,
+ robot_size)
assert rx, 'Cannot found path'
if show_animation: # pragma: no cover
plt.plot(rx, ry, "-r")
+ plt.pause(0.1)
plt.show()
diff --git a/PathPlanning/WavefrontCPP/map/test.png b/PathPlanning/WavefrontCPP/map/test.png
new file mode 100644
index 0000000000..4abca0bf30
Binary files /dev/null and b/PathPlanning/WavefrontCPP/map/test.png differ
diff --git a/PathPlanning/WavefrontCPP/map/test_2.png b/PathPlanning/WavefrontCPP/map/test_2.png
new file mode 100644
index 0000000000..0d27fa9f95
Binary files /dev/null and b/PathPlanning/WavefrontCPP/map/test_2.png differ
diff --git a/PathPlanning/WavefrontCPP/map/test_3.png b/PathPlanning/WavefrontCPP/map/test_3.png
new file mode 100644
index 0000000000..1a50b87ccf
Binary files /dev/null and b/PathPlanning/WavefrontCPP/map/test_3.png differ
diff --git a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py
new file mode 100644
index 0000000000..c5a139454b
--- /dev/null
+++ b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py
@@ -0,0 +1,218 @@
+"""
+Distance/Path Transform Wavefront Coverage Path Planner
+
+author: Todd Tang
+paper: Planning paths of complete coverage of an unstructured environment
+ by a mobile robot - Zelinsky et.al.
+link: https://pinkwink.kr/attachment/cfile3.uf@1354654A4E8945BD13FE77.pdf
+"""
+
+import os
+import sys
+
+import matplotlib.pyplot as plt
+import numpy as np
+from scipy import ndimage
+
+do_animation = True
+
+
+def transform(
+ grid_map, src, distance_type='chessboard',
+ transform_type='path', alpha=0.01
+):
+ """transform
+
+ calculating transform of transform_type from src
+ in given distance_type
+
+ :param grid_map: 2d binary map
+ :param src: distance transform source
+ :param distance_type: type of distance used
+ :param transform_type: type of transform used
+ :param alpha: weight of Obstacle Transform used when using path_transform
+ """
+
+ n_rows, n_cols = grid_map.shape
+
+ if n_rows == 0 or n_cols == 0:
+ sys.exit('Empty grid_map.')
+
+ inc_order = [[0, 1], [1, 1], [1, 0], [1, -1],
+ [0, -1], [-1, -1], [-1, 0], [-1, 1]]
+ if distance_type == 'chessboard':
+ cost = [1, 1, 1, 1, 1, 1, 1, 1]
+ elif distance_type == 'eculidean':
+ cost = [1, np.sqrt(2), 1, np.sqrt(2), 1, np.sqrt(2), 1, np.sqrt(2)]
+ else:
+ sys.exit('Unsupported distance type.')
+
+ transform_matrix = float('inf') * np.ones_like(grid_map, dtype=float)
+ transform_matrix[src[0], src[1]] = 0
+ if transform_type == 'distance':
+ eT = np.zeros_like(grid_map)
+ elif transform_type == 'path':
+ eT = ndimage.distance_transform_cdt(1 - grid_map, distance_type)
+ else:
+ sys.exit('Unsupported transform type.')
+
+ # set obstacle transform_matrix value to infinity
+ for i in range(n_rows):
+ for j in range(n_cols):
+ if grid_map[i][j] == 1.0:
+ transform_matrix[i][j] = float('inf')
+ is_visited = np.zeros_like(transform_matrix, dtype=bool)
+ is_visited[src[0], src[1]] = True
+ traversal_queue = [src]
+ calculated = set([(src[0] - 1) * n_cols + src[1]])
+
+ def is_valid_neighbor(g_i, g_j):
+ return 0 <= g_i < n_rows and 0 <= g_j < n_cols \
+ and not grid_map[g_i][g_j]
+
+ while traversal_queue:
+ i, j = traversal_queue.pop(0)
+ for k, inc in enumerate(inc_order):
+ ni = i + inc[0]
+ nj = j + inc[1]
+ if is_valid_neighbor(ni, nj):
+ is_visited[i][j] = True
+
+ # update transform_matrix
+ transform_matrix[i][j] = min(
+ transform_matrix[i][j],
+ transform_matrix[ni][nj] + cost[k] + alpha * eT[ni][nj])
+
+ if not is_visited[ni][nj] \
+ and ((ni - 1) * n_cols + nj) not in calculated:
+ traversal_queue.append((ni, nj))
+ calculated.add((ni - 1) * n_cols + nj)
+
+ return transform_matrix
+
+
+def get_search_order_increment(start, goal):
+ if start[0] >= goal[0] and start[1] >= goal[1]:
+ order = [[1, 0], [0, 1], [-1, 0], [0, -1],
+ [1, 1], [1, -1], [-1, 1], [-1, -1]]
+ elif start[0] <= goal[0] and start[1] >= goal[1]:
+ order = [[-1, 0], [0, 1], [1, 0], [0, -1],
+ [-1, 1], [-1, -1], [1, 1], [1, -1]]
+ elif start[0] >= goal[0] and start[1] <= goal[1]:
+ order = [[1, 0], [0, -1], [-1, 0], [0, 1],
+ [1, -1], [-1, -1], [1, 1], [-1, 1]]
+ elif start[0] <= goal[0] and start[1] <= goal[1]:
+ order = [[-1, 0], [0, -1], [0, 1], [1, 0],
+ [-1, -1], [-1, 1], [1, -1], [1, 1]]
+ else:
+ sys.exit('get_search_order_increment: cannot determine \
+ start=>goal increment order')
+ return order
+
+
+def wavefront(transform_matrix, start, goal):
+ """wavefront
+
+ performing wavefront coverage path planning
+
+ :param transform_matrix: the transform matrix
+ :param start: start point of planning
+ :param goal: goal point of planning
+ """
+
+ path = []
+ n_rows, n_cols = transform_matrix.shape
+
+ def is_valid_neighbor(g_i, g_j):
+ is_i_valid_bounded = 0 <= g_i < n_rows
+ is_j_valid_bounded = 0 <= g_j < n_cols
+ if is_i_valid_bounded and is_j_valid_bounded:
+ return not is_visited[g_i][g_j] and \
+ transform_matrix[g_i][g_j] != float('inf')
+ return False
+
+ inc_order = get_search_order_increment(start, goal)
+
+ current_node = start
+ is_visited = np.zeros_like(transform_matrix, dtype=bool)
+
+ while current_node != goal:
+ i, j = current_node
+ path.append((i, j))
+ is_visited[i][j] = True
+
+ max_T = float('-inf')
+ i_max = (-1, -1)
+ i_last = 0
+ for i_last in range(len(path)):
+ current_node = path[-1 - i_last] # get latest node in path
+ for ci, cj in inc_order:
+ ni, nj = current_node[0] + ci, current_node[1] + cj
+ if is_valid_neighbor(ni, nj) and \
+ transform_matrix[ni][nj] > max_T:
+ i_max = (ni, nj)
+ max_T = transform_matrix[ni][nj]
+
+ if i_max != (-1, -1):
+ break
+
+ if i_max == (-1, -1):
+ break
+ else:
+ current_node = i_max
+ if i_last != 0:
+ print('backtracing to', current_node)
+ path.append(goal)
+
+ return path
+
+
+def visualize_path(grid_map, start, goal, path): # pragma: no cover
+ oy, ox = start
+ gy, gx = goal
+ px, py = np.transpose(np.flipud(np.fliplr(path)))
+
+ if not do_animation:
+ plt.imshow(grid_map, cmap='Greys')
+ plt.plot(ox, oy, "-xy")
+ plt.plot(px, py, "-r")
+ plt.plot(gx, gy, "-pg")
+ plt.show()
+ else:
+ for ipx, ipy in zip(px, py):
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.imshow(grid_map, cmap='Greys')
+ plt.plot(ox, oy, "-xb")
+ plt.plot(px, py, "-r")
+ plt.plot(gx, gy, "-pg")
+ plt.plot(ipx, ipy, "or")
+ plt.axis("equal")
+ plt.grid(True)
+ plt.pause(0.1)
+
+
+def main():
+ dir_path = os.path.dirname(os.path.realpath(__file__))
+ img = plt.imread(os.path.join(dir_path, 'map', 'test.png'))
+ img = 1 - img # revert pixel values
+
+ start = (43, 0)
+ goal = (0, 0)
+
+ # distance transform wavefront
+ DT = transform(img, goal, transform_type='distance')
+ DT_path = wavefront(DT, start, goal)
+ visualize_path(img, start, goal, DT_path)
+
+ # path transform wavefront
+ PT = transform(img, goal, transform_type='path', alpha=0.01)
+ PT_path = wavefront(PT, start, goal)
+ visualize_path(img, start, goal, PT_path)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/PathTracking/__init__.py b/PathTracking/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathTracking/cgmres_nmpc/Figure_1.png b/PathTracking/cgmres_nmpc/Figure_1.png
deleted file mode 100644
index c15112dcac..0000000000
Binary files a/PathTracking/cgmres_nmpc/Figure_1.png and /dev/null differ
diff --git a/PathTracking/cgmres_nmpc/Figure_2.png b/PathTracking/cgmres_nmpc/Figure_2.png
deleted file mode 100644
index 99ebc493d0..0000000000
Binary files a/PathTracking/cgmres_nmpc/Figure_2.png and /dev/null differ
diff --git a/PathTracking/cgmres_nmpc/Figure_3.png b/PathTracking/cgmres_nmpc/Figure_3.png
deleted file mode 100644
index 4c7d020734..0000000000
Binary files a/PathTracking/cgmres_nmpc/Figure_3.png and /dev/null differ
diff --git a/PathTracking/cgmres_nmpc/Figure_4.png b/PathTracking/cgmres_nmpc/Figure_4.png
deleted file mode 100644
index 1c0406a8e9..0000000000
Binary files a/PathTracking/cgmres_nmpc/Figure_4.png and /dev/null differ
diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb b/PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb
deleted file mode 100644
index 04fa940a8f..0000000000
--- a/PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb
+++ /dev/null
@@ -1,208 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Nonlinear Model Predictive Control with C-GMRES"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 10,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 10,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"Figure_4.png\",width=600)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 9,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 9,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "Image(filename=\"Figure_1.png\",width=600)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 8,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 8,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "Image(filename=\"Figure_2.png\",width=600)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 7,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 7,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "Image(filename=\"Figure_3.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- ""
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Mathematical Formulation\n",
- "\n",
- "Motion model is\n",
- "\n",
- "$$\\dot{x}=vcos\\theta$$\n",
- "\n",
- "$$\\dot{y}=vsin\\theta$$\n",
- "\n",
- "$$\\dot{\\theta}=\\frac{v}{WB}sin(u_{\\delta})$$ (tan is not good for optimization)\n",
- "\n",
- "$$\\dot{v}=u_a$$\n",
- "\n",
- "Cost function is \n",
- "\n",
- "$$J=\\frac{1}{2}(u_a^2+u_{\\delta}^2)-\\phi_a d_a-\\phi_\\delta d_\\delta$$\n",
- "\n",
- "Input constraints are\n",
- "\n",
- "$$|u_a| \\leq u_{a,max}$$\n",
- "\n",
- "$$|u_\\delta| \\leq u_{\\delta,max}$$\n",
- "\n",
- "So, Hamiltonian is\n",
- "\n",
- "$$J=\\frac{1}{2}(u_a^2+u_{\\delta}^2)-\\phi_a d_a-\\phi_\\delta d_\\delta\\\\ +\\lambda_1vcos\\theta+\\lambda_2vsin\\theta+\\lambda_3\\frac{v}{WB}sin(u_{\\delta})+\\lambda_4u_a\\\\ \n",
- "+\\rho_1(u_a^2+d_a^2+u_{a,max}^2)+\\rho_2(u_\\delta^2+d_\\delta^2+u_{\\delta,max}^2)$$\n",
- "\n",
- "Partial differential equations of the Hamiltonian are:\n",
- "\n",
- "$\\begin{equation*}\n",
- "\\frac{\\partial H}{\\partial \\bf{x}}=\\\\ \n",
- "\\begin{bmatrix}\n",
- "\\frac{\\partial H}{\\partial x}= 0&\\\\\n",
- "\\frac{\\partial H}{\\partial y}= 0&\\\\\n",
- "\\frac{\\partial H}{\\partial \\theta}= -\\lambda_1vsin\\theta+\\lambda_2vcos\\theta&\\\\\n",
- "\\frac{\\partial H}{\\partial v}=-\\lambda_1cos\\theta+\\lambda_2sin\\theta+\\lambda_3\\frac{1}{WB}sin(u_{\\delta})&\\\\\n",
- "\\end{bmatrix}\n",
- "\\\\\n",
- "\\end{equation*}$\n",
- "\n",
- "\n",
- "$\\begin{equation*}\n",
- "\\frac{\\partial H}{\\partial \\bf{u}}=\\\\ \n",
- "\\begin{bmatrix}\n",
- "\\frac{\\partial H}{\\partial u_a}= u_a+\\lambda_4+2\\rho_1u_a&\\\\\n",
- "\\frac{\\partial H}{\\partial u_\\delta}= u_\\delta+\\lambda_3\\frac{v}{WB}cos(u_{\\delta})+2\\rho_2u_\\delta&\\\\\n",
- "\\frac{\\partial H}{\\partial d_a}= -\\phi_a+2\\rho_1d_a&\\\\\n",
- "\\frac{\\partial H}{\\partial d_\\delta}=-\\phi_\\delta+2\\rho_2d_\\delta&\\\\\n",
- "\\end{bmatrix}\n",
- "\\\\\n",
- "\\end{equation*}$"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Ref\n",
- "\n",
- "- [Shunichi09/nonlinear\\_control: Implementing the nonlinear model predictive control, sliding mode control](https://github.com/Shunichi09/nonlinear_control)\n",
- "\n",
- "- [非線形モデル予測制御におけるCGMRES法をpythonで実装する \\- Qiita](https://qiita.com/MENDY/items/4108190a579395053924)"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.8"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py
index 74a0f9cc57..ee40e73504 100644
--- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py
+++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py
@@ -4,18 +4,19 @@
author Atsushi Sakai (@Atsushi_twi)
-Ref:
-
-- Shunichi09/nonlinear_control: Implementing the nonlinear model predictive control, sliding mode control https://github.com/Shunichi09/nonlinear_control
+Reference:
+Shunichi09/nonlinear_control: Implementing the nonlinear model predictive
+control, sliding mode control https://github.com/Shunichi09/PythonLinearNonlinearControl
"""
-import numpy as np
+from math import cos, sin, radians, atan2
+
import matplotlib.pyplot as plt
-import math
+import numpy as np
U_A_MAX = 1.0
-U_OMEGA_MAX = math.radians(45.0)
+U_OMEGA_MAX = radians(45.0)
PHI_V = 0.01
PHI_OMEGA = 0.01
WB = 0.25 # [m] wheel base
@@ -24,19 +25,18 @@
def differential_model(v, yaw, u_1, u_2):
-
- dx = math.cos(yaw) * v
- dy = math.sin(yaw) * v
+ dx = cos(yaw) * v
+ dy = sin(yaw) * v
dv = u_1
- dyaw = v / WB * math.sin(u_2) # tan is not good for nonlinear optimization
+ # tangent is not good for nonlinear optimization
+ d_yaw = v / WB * sin(u_2)
- return dx, dy, dyaw, dv
+ return dx, dy, d_yaw, dv
-class TwoWheeledSystem():
+class TwoWheeledSystem:
def __init__(self, init_x, init_y, init_yaw, init_v):
-
self.x = init_x
self.y = init_y
self.yaw = init_yaw
@@ -47,12 +47,11 @@ def __init__(self, init_x, init_y, init_yaw, init_v):
self.history_v = [init_v]
def update_state(self, u_1, u_2, dt=0.01):
-
- dx, dy, dyaw, dv = differential_model(self.v, self.yaw, u_1, u_2)
+ dx, dy, d_yaw, dv = differential_model(self.v, self.yaw, u_1, u_2)
self.x += dt * dx
self.y += dt * dy
- self.yaw += dt * dyaw
+ self.yaw += dt * d_yaw
self.v += dt * dv
# save
@@ -62,13 +61,15 @@ def update_state(self, u_1, u_2, dt=0.01):
self.history_v.append(self.v)
-class NMPCSimulatorSystem():
+class NMPCSimulatorSystem:
def calc_predict_and_adjoint_state(self, x, y, yaw, v, u_1s, u_2s, N, dt):
+ # by using state equation
x_s, y_s, yaw_s, v_s = self._calc_predict_states(
- x, y, yaw, v, u_1s, u_2s, N, dt) # by using state equation
+ x, y, yaw, v, u_1s, u_2s, N, dt)
+ # by using adjoint equation
lam_1s, lam_2s, lam_3s, lam_4s = self._calc_adjoint_states(
- x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt) # by using adjoint equation
+ x_s, y_s, yaw_s, v_s, u_2s, N, dt)
return x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s
@@ -88,7 +89,7 @@ def _calc_predict_states(self, x, y, yaw, v, u_1s, u_2s, N, dt):
return x_s, y_s, yaw_s, v_s
- def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt):
+ def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_2s, N, dt):
lam_1s = [x_s[-1]]
lam_2s = [y_s[-1]]
lam_3s = [yaw_s[-1]]
@@ -97,8 +98,8 @@ def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt):
# backward adjoint state calc
for i in range(N - 1, 0, -1):
temp_lam_1, temp_lam_2, temp_lam_3, temp_lam_4 = self._adjoint_state_with_oylar(
- x_s[i], y_s[i], yaw_s[i], v_s[i], lam_1s[0], lam_2s[0], lam_3s[0], lam_4s[0],
- u_1s[i], u_2s[i], dt)
+ yaw_s[i], v_s[i], lam_1s[0], lam_2s[0], lam_3s[0], lam_4s[0],
+ u_2s[i], dt)
lam_1s.insert(0, temp_lam_1)
lam_2s.insert(0, temp_lam_2)
lam_3s.insert(0, temp_lam_3)
@@ -106,7 +107,8 @@ def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt):
return lam_1s, lam_2s, lam_3s, lam_4s
- def _predict_state_with_oylar(self, x, y, yaw, v, u_1, u_2, dt):
+ @staticmethod
+ def _predict_state_with_oylar(x, y, yaw, v, u_1, u_2, dt):
dx, dy, dyaw, dv = differential_model(
v, yaw, u_1, u_2)
@@ -118,21 +120,21 @@ def _predict_state_with_oylar(self, x, y, yaw, v, u_1, u_2, dt):
return next_x_1, next_x_2, next_x_3, next_x_4
- def _adjoint_state_with_oylar(self, x, y, yaw, v, lam_1, lam_2, lam_3, lam_4, u_1, u_2, dt):
+ @staticmethod
+ def _adjoint_state_with_oylar(yaw, v, lam_1, lam_2, lam_3, lam_4, u_2, dt):
# ∂H/∂x
pre_lam_1 = lam_1 + dt * 0.0
pre_lam_2 = lam_2 + dt * 0.0
- pre_lam_3 = lam_3 + dt * \
- (- lam_1 * math.sin(yaw) * v + lam_2 * math.cos(yaw) * v)
- pre_lam_4 = lam_4 + dt * \
- (lam_1 * math.cos(yaw) + lam_2 *
- math.sin(yaw) + lam_3 * math.sin(u_2) / WB)
+ tmp1 = - lam_1 * sin(yaw) * v + lam_2 * cos(yaw) * v
+ pre_lam_3 = lam_3 + dt * tmp1
+ tmp2 = lam_1 * cos(yaw) + lam_2 * sin(yaw) + lam_3 * sin(u_2) / WB
+ pre_lam_4 = lam_4 + dt * tmp2
return pre_lam_1, pre_lam_2, pre_lam_3, pre_lam_4
-class NMPCController_with_CGMRES():
+class NMPCControllerCGMRES:
"""
Attributes
------------
@@ -145,7 +147,7 @@ class NMPCController_with_CGMRES():
alpha : float
gain of predict time
N : int
- predicte step, discritize value
+ predict step, discrete value
threshold : float
cgmres's threshold value
input_num : int
@@ -226,20 +228,22 @@ def calc_input(self, x, y, yaw, v, time):
dx_4 = x_4_dot * self.ht
x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state(
- x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s, self.u_2s, self.N, dt)
+ x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s, self.u_2s,
+ self.N, dt)
# Fxt:F(U,x+hx˙,t+h)
- Fxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
- self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s,
- self.raw_1s, self.raw_2s, self.N, dt)
+ Fxt = self._calc_f(v_s, lam_3s, lam_4s,
+ self.u_1s, self.u_2s, self.dummy_u_1s,
+ self.dummy_u_2s,
+ self.raw_1s, self.raw_2s, self.N)
# F:F(U,x,t)
x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state(
x, y, yaw, v, self.u_1s, self.u_2s, self.N, dt)
- F = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
+ F = self._calc_f(v_s, lam_3s, lam_4s,
self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s,
- self.raw_1s, self.raw_2s, self.N, dt)
+ self.raw_1s, self.raw_2s, self.N)
right = -self.zeta * F - ((Fxt - F) / self.ht)
@@ -251,17 +255,19 @@ def calc_input(self, x, y, yaw, v, time):
draw_2 = self.raw_2s * self.ht
x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state(
- x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, self.u_2s + du_2, self.N, dt)
+ x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1,
+ self.u_2s + du_2, self.N, dt)
# Fuxt:F(U+hdU(0),x+hx˙,t+h)
- Fuxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
+ Fuxt = self._calc_f(v_s, lam_3s, lam_4s,
self.u_1s + du_1, self.u_2s + du_2,
- self.dummy_u_1s + ddummy_u_1, self.dummy_u_2s + ddummy_u_2,
- self.raw_1s + draw_1, self.raw_2s + draw_2, self.N, dt)
+ self.dummy_u_1s + ddummy_u_1,
+ self.dummy_u_2s + ddummy_u_2,
+ self.raw_1s + draw_1, self.raw_2s + draw_2, self.N)
left = ((Fuxt - Fxt) / self.ht)
- # calculationg cgmres
+ # calculating cgmres
r0 = right - left
r0_norm = np.linalg.norm(r0)
@@ -276,6 +282,9 @@ def calc_input(self, x, y, yaw, v, time):
ys_pre = None
+ du_1_new, du_2_new, draw_1_new, draw_2_new = None, None, None, None
+ ddummy_u_1_new, ddummy_u_2_new = None, None
+
for i in range(self.max_iteration):
du_1 = vs[::self.input_num, i] * self.ht
du_2 = vs[1::self.input_num, i] * self.ht
@@ -285,12 +294,15 @@ def calc_input(self, x, y, yaw, v, time):
draw_2 = vs[5::self.input_num, i] * self.ht
x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state(
- x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, self.u_2s + du_2, self.N, dt)
+ x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1,
+ self.u_2s + du_2, self.N, dt)
- Fuxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
+ Fuxt = self._calc_f(v_s, lam_3s, lam_4s,
self.u_1s + du_1, self.u_2s + du_2,
- self.dummy_u_1s + ddummy_u_1, self.dummy_u_2s + ddummy_u_2,
- self.raw_1s + draw_1, self.raw_2s + draw_2, self.N, dt)
+ self.dummy_u_1s + ddummy_u_1,
+ self.dummy_u_2s + ddummy_u_2,
+ self.raw_1s + draw_1, self.raw_2s + draw_2,
+ self.N)
Av = ((Fuxt - Fxt) / self.ht)
@@ -312,14 +324,17 @@ def calc_input(self, x, y, yaw, v, time):
judge_value = r0_norm * e[:i + 1] - np.dot(hs[:i + 1, :i], ys[:i])
- if np.linalg.norm(judge_value) < self.threshold or i == self.max_iteration - 1:
- update_value = np.dot(vs[:, :i - 1], ys_pre[:i - 1]).flatten()
- du_1_new = du_1 + update_value[::self.input_num]
- du_2_new = du_2 + update_value[1::self.input_num]
- ddummy_u_1_new = ddummy_u_1 + update_value[2::self.input_num]
- ddummy_u_2_new = ddummy_u_2 + update_value[3::self.input_num]
- draw_1_new = draw_1 + update_value[4::self.input_num]
- draw_2_new = draw_2 + update_value[5::self.input_num]
+ flag1 = np.linalg.norm(judge_value) < self.threshold
+
+ flag2 = i == self.max_iteration - 1
+ if flag1 or flag2:
+ update_val = np.dot(vs[:, :i - 1], ys_pre[:i - 1]).flatten()
+ du_1_new = du_1 + update_val[::self.input_num]
+ du_2_new = du_2 + update_val[1::self.input_num]
+ ddummy_u_1_new = ddummy_u_1 + update_val[2::self.input_num]
+ ddummy_u_2_new = ddummy_u_2 + update_val[3::self.input_num]
+ draw_1_new = draw_1 + update_val[4::self.input_num]
+ draw_2_new = draw_2 + update_val[5::self.input_num]
break
ys_pre = ys
@@ -335,9 +350,9 @@ def calc_input(self, x, y, yaw, v, time):
x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state(
x, y, yaw, v, self.u_1s, self.u_2s, self.N, dt)
- F = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
+ F = self._calc_f(v_s, lam_3s, lam_4s,
self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s,
- self.raw_1s, self.raw_2s, self.N, dt)
+ self.raw_1s, self.raw_2s, self.N)
print("norm(F) = {0}".format(np.linalg.norm(F)))
@@ -352,36 +367,38 @@ def calc_input(self, x, y, yaw, v, time):
return self.u_1s, self.u_2s
- def _calc_f(self, x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s,
- u_1s, u_2s, dummy_u_1s, dummy_u_2s, raw_1s, raw_2s, N, dt):
+ @staticmethod
+ def _calc_f(v_s, lam_3s, lam_4s, u_1s, u_2s, dummy_u_1s, dummy_u_2s,
+ raw_1s, raw_2s, N):
F = []
for i in range(N):
# ∂H/∂u(xi, ui, λi)
F.append(u_1s[i] + lam_4s[i] + 2.0 * raw_1s[i] * u_1s[i])
F.append(u_2s[i] + lam_3s[i] * v_s[i] /
- WB * math.cos(u_2s[i])**2 + 2.0 * raw_2s[i] * u_2s[i])
+ WB * cos(u_2s[i]) ** 2 + 2.0 * raw_2s[i] * u_2s[i])
F.append(-PHI_V + 2.0 * raw_1s[i] * dummy_u_1s[i])
F.append(-PHI_OMEGA + 2.0 * raw_2s[i] * dummy_u_2s[i])
# C(xi, ui, λi)
- F.append(u_1s[i]**2 + dummy_u_1s[i]**2 - U_A_MAX**2)
- F.append(u_2s[i]**2 + dummy_u_2s[i]**2 - U_OMEGA_MAX**2)
+ F.append(u_1s[i] ** 2 + dummy_u_1s[i] ** 2 - U_A_MAX ** 2)
+ F.append(u_2s[i] ** 2 + dummy_u_2s[i] ** 2 - U_OMEGA_MAX ** 2)
return np.array(F)
-def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cover
+def plot_figures(plant_system, controller, iteration_num,
+ dt): # pragma: no cover
# figure
# time history
fig_p = plt.figure()
fig_u = plt.figure()
fig_f = plt.figure()
- # traj
+ # trajectory
fig_t = plt.figure()
- fig_traj = fig_t.add_subplot(111)
- fig_traj.set_aspect('equal')
+ fig_trajectory = fig_t.add_subplot(111)
+ fig_trajectory.set_aspect('equal')
x_1_fig = fig_p.add_subplot(411)
x_2_fig = fig_p.add_subplot(412)
@@ -443,11 +460,11 @@ def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cov
f_fig.set_xlabel("time [s]")
f_fig.set_ylabel("optimal error")
- fig_traj.plot(plant_system.history_x,
- plant_system.history_y, "-r")
- fig_traj.set_xlabel("x [m]")
- fig_traj.set_ylabel("y [m]")
- fig_traj.axis("equal")
+ fig_trajectory.plot(plant_system.history_x,
+ plant_system.history_y, "-r")
+ fig_trajectory.set_xlabel("x [m]")
+ fig_trajectory.set_ylabel("y [m]")
+ fig_trajectory.axis("equal")
# start state
plot_car(plant_system.history_x[0],
@@ -462,23 +479,25 @@ def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cov
plt.show()
-def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: no cover
+def plot_car(x, y, yaw, steer=0.0, truck_color="-k"): # pragma: no cover
# Vehicle parameters
LENGTH = 0.4 # [m]
WIDTH = 0.2 # [m]
- BACKTOWHEEL = 0.1 # [m]
+ BACK_TO_WHEEL = 0.1 # [m]
WHEEL_LEN = 0.03 # [m]
WHEEL_WIDTH = 0.02 # [m]
TREAD = 0.07 # [m]
- outline = np.array([[-BACKTOWHEEL, (LENGTH - BACKTOWHEEL), (LENGTH - BACKTOWHEEL),
- -BACKTOWHEEL, -BACKTOWHEEL],
- [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]])
+ outline = np.array(
+ [[-BACK_TO_WHEEL, (LENGTH - BACK_TO_WHEEL), (LENGTH - BACK_TO_WHEEL),
+ -BACK_TO_WHEEL, -BACK_TO_WHEEL],
+ [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]])
- fr_wheel = np.array([[WHEEL_LEN, -WHEEL_LEN, -WHEEL_LEN, WHEEL_LEN, WHEEL_LEN],
- [-WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD, WHEEL_WIDTH -
- TREAD, WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD]])
+ fr_wheel = np.array(
+ [[WHEEL_LEN, -WHEEL_LEN, -WHEEL_LEN, WHEEL_LEN, WHEEL_LEN],
+ [-WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD, WHEEL_WIDTH -
+ TREAD, WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD]])
rr_wheel = np.copy(fr_wheel)
@@ -487,10 +506,10 @@ def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: n
rl_wheel = np.copy(rr_wheel)
rl_wheel[1, :] *= -1
- Rot1 = np.array([[math.cos(yaw), math.sin(yaw)],
- [-math.sin(yaw), math.cos(yaw)]])
- Rot2 = np.array([[math.cos(steer), math.sin(steer)],
- [-math.sin(steer), math.cos(steer)]])
+ Rot1 = np.array([[cos(yaw), sin(yaw)],
+ [-sin(yaw), cos(yaw)]])
+ Rot2 = np.array([[cos(steer), sin(steer)],
+ [-sin(steer), cos(steer)]])
fr_wheel = (fr_wheel.T.dot(Rot2)).T
fl_wheel = (fl_wheel.T.dot(Rot2)).T
@@ -516,20 +535,19 @@ def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: n
rl_wheel[1, :] += y
plt.plot(np.array(outline[0, :]).flatten(),
- np.array(outline[1, :]).flatten(), truckcolor)
+ np.array(outline[1, :]).flatten(), truck_color)
plt.plot(np.array(fr_wheel[0, :]).flatten(),
- np.array(fr_wheel[1, :]).flatten(), truckcolor)
+ np.array(fr_wheel[1, :]).flatten(), truck_color)
plt.plot(np.array(rr_wheel[0, :]).flatten(),
- np.array(rr_wheel[1, :]).flatten(), truckcolor)
+ np.array(rr_wheel[1, :]).flatten(), truck_color)
plt.plot(np.array(fl_wheel[0, :]).flatten(),
- np.array(fl_wheel[1, :]).flatten(), truckcolor)
+ np.array(fl_wheel[1, :]).flatten(), truck_color)
plt.plot(np.array(rl_wheel[0, :]).flatten(),
- np.array(rl_wheel[1, :]).flatten(), truckcolor)
+ np.array(rl_wheel[1, :]).flatten(), truck_color)
plt.plot(x, y, "*")
def animation(plant, controller, dt):
-
skip = 2 # skip index for animation
for t in range(1, len(controller.history_u_1), skip):
@@ -543,9 +561,13 @@ def animation(plant, controller, dt):
if abs(v) <= 0.01:
steer = 0.0
else:
- steer = math.atan2(controller.history_u_2[t] * WB / v, 1.0)
+ steer = atan2(controller.history_u_2[t] * WB / v, 1.0)
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(plant.history_x, plant.history_y, "-r", label="trajectory")
plot_car(x, y, yaw, steer=steer)
plt.axis("equal")
@@ -565,7 +587,7 @@ def main():
init_x = -4.5
init_y = -2.5
- init_yaw = math.radians(45.0)
+ init_yaw = radians(45.0)
init_v = -1.0
# plant
@@ -573,14 +595,15 @@ def main():
init_x, init_y, init_yaw, init_v)
# controller
- controller = NMPCController_with_CGMRES()
+ controller = NMPCControllerCGMRES()
iteration_num = int(iteration_time / dt)
for i in range(1, iteration_num):
time = float(i) * dt
# make input
u_1s, u_2s = controller.calc_input(
- plant_system.x, plant_system.y, plant_system.yaw, plant_system.v, time)
+ plant_system.x, plant_system.y, plant_system.yaw, plant_system.v,
+ time)
# update state
plant_system.update_state(u_1s[0], u_2s[0])
diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py
index ff8d890d0f..5831d02d30 100644
--- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py
+++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py
@@ -7,20 +7,20 @@
"""
import math
import sys
-
import matplotlib.pyplot as plt
import numpy as np
import scipy.linalg as la
+import pathlib
-sys.path.append("../../PathPlanning/CubicSpline/")
-import cubic_spline_planner
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
+from PathPlanning.CubicSpline import cubic_spline_planner
+# === Parameters =====
# LQR parameter
-Q = np.eye(5)
-R = np.eye(2)
-
-# parameters
+lqr_Q = np.eye(5)
+lqr_R = np.eye(2)
dt = 0.1 # time tick[s]
L = 0.5 # Wheel base of the vehicle [m]
max_steer = np.deg2rad(45.0) # maximum steering angle[rad]
@@ -53,26 +53,26 @@ def update(state, a, delta):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
-def solve_DARE(A, B, Q, R):
+def solve_dare(A, B, Q, R):
"""
solve a discrete time_Algebraic Riccati equation (DARE)
"""
- X = Q
- Xn = Q
- maxiter = 150
+ x = Q
+ x_next = Q
+ max_iter = 150
eps = 0.01
- for i in range(maxiter):
- Xn = A.T @ X @ A - A.T @ X @ B @ \
- la.inv(R + B.T @ X @ B) @ B.T @ X @ A + Q
- if (abs(Xn - X)).max() < eps:
+ for i in range(max_iter):
+ x_next = A.T @ x @ A - A.T @ x @ B @ \
+ la.inv(R + B.T @ x @ B) @ B.T @ x @ A + Q
+ if (abs(x_next - x)).max() < eps:
break
- X = Xn
+ x = x_next
- return Xn
+ return x_next
def dlqr(A, B, Q, R):
@@ -83,17 +83,17 @@ def dlqr(A, B, Q, R):
"""
# first, try to solve the ricatti equation
- X = solve_DARE(A, B, Q, R)
+ X = solve_dare(A, B, Q, R)
# compute the LQR gain
K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A)
- eigs = la.eig(A - B @ K)
+ eig_result = la.eig(A - B @ K)
- return K, X, eigs[0]
+ return K, X, eig_result[0]
-def lqr_steering_control(state, cx, cy, cyaw, ck, pe, pth_e, sp):
+def lqr_speed_steering_control(state, cx, cy, cyaw, ck, pe, pth_e, sp, Q, R):
ind, e = calc_nearest_index(state, cx, cy, cyaw)
tv = sp[ind]
@@ -102,6 +102,11 @@ def lqr_steering_control(state, cx, cy, cyaw, ck, pe, pth_e, sp):
v = state.v
th_e = pi_2_pi(state.yaw - cyaw[ind])
+ # A = [1.0, dt, 0.0, 0.0, 0.0
+ # 0.0, 0.0, v, 0.0, 0.0]
+ # 0.0, 0.0, 1.0, dt, 0.0]
+ # 0.0, 0.0, 0.0, 0.0, 0.0]
+ # 0.0, 0.0, 0.0, 0.0, 1.0]
A = np.zeros((5, 5))
A[0, 0] = 1.0
A[0, 1] = dt
@@ -109,35 +114,47 @@ def lqr_steering_control(state, cx, cy, cyaw, ck, pe, pth_e, sp):
A[2, 2] = 1.0
A[2, 3] = dt
A[4, 4] = 1.0
- # print(A)
+ # B = [0.0, 0.0
+ # 0.0, 0.0
+ # 0.0, 0.0
+ # v/L, 0.0
+ # 0.0, dt]
B = np.zeros((5, 2))
B[3, 0] = v / L
B[4, 1] = dt
K, _, _ = dlqr(A, B, Q, R)
+ # state vector
+ # x = [e, dot_e, th_e, dot_th_e, delta_v]
+ # e: lateral distance to the path
+ # dot_e: derivative of e
+ # th_e: angle difference to the path
+ # dot_th_e: derivative of th_e
+ # delta_v: difference between current speed and target speed
x = np.zeros((5, 1))
-
x[0, 0] = e
x[1, 0] = (e - pe) / dt
x[2, 0] = th_e
x[3, 0] = (th_e - pth_e) / dt
x[4, 0] = v - tv
+ # input vector
+ # u = [delta, accel]
+ # delta: steering angle
+ # accel: acceleration
ustar = -K @ x
# calc steering input
-
- ff = math.atan2(L * k, 1)
- fb = pi_2_pi(ustar[0, 0])
+ ff = math.atan2(L * k, 1) # feedforward steering angle
+ fb = pi_2_pi(ustar[0, 0]) # feedback steering angle
+ delta = ff + fb
# calc accel input
- ai = ustar[1, 0]
+ accel = ustar[1, 0]
- delta = ff + fb
-
- return delta, ind, e, th_e, ai
+ return delta, ind, e, th_e, accel
def calc_nearest_index(state, cx, cy, cyaw):
@@ -162,7 +179,7 @@ def calc_nearest_index(state, cx, cy, cyaw):
return ind, mind
-def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
+def do_simulation(cx, cy, cyaw, ck, speed_profile, goal):
T = 500.0 # max simulation time
goal_dis = 0.3
stop_speed = 0.05
@@ -179,8 +196,8 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
e, e_th = 0.0, 0.0
while T >= time:
- dl, target_ind, e, e_th, ai = lqr_steering_control(
- state, cx, cy, cyaw, ck, e, e_th, speed_profile)
+ dl, target_ind, e, e_th, ai = lqr_speed_steering_control(
+ state, cx, cy, cyaw, ck, e, e_th, speed_profile, lqr_Q, lqr_R)
state = update(state, ai, dl)
@@ -192,7 +209,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
# check goal
dx = state.x - goal[0]
dy = state.y - goal[1]
- if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
+ if math.hypot(dx, dy) <= goal_dis:
print("Goal")
break
@@ -204,6 +221,10 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
if target_ind % 1 == 0 and show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(cx, cy, "-r", label="course")
plt.plot(x, y, "ob", label="trajectory")
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
@@ -216,13 +237,13 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
return t, x, y, yaw, v
-def calc_speed_profile(cx, cy, cyaw, target_speed):
- speed_profile = [target_speed] * len(cx)
+def calc_speed_profile(cyaw, target_speed):
+ speed_profile = [target_speed] * len(cyaw)
direction = 1.0
# Set stop point
- for i in range(len(cx) - 1):
+ for i in range(len(cyaw) - 1):
dyaw = abs(cyaw[i + 1] - cyaw[i])
switch = math.pi / 4.0 <= dyaw < math.pi / 2.0
@@ -256,9 +277,9 @@ def main():
ax, ay, ds=0.1)
target_speed = 10.0 / 3.6 # simulation parameter km/h -> m/s
- sp = calc_speed_profile(cx, cy, cyaw, target_speed)
+ sp = calc_speed_profile(cyaw, target_speed)
- t, x, y, yaw, v = closed_loop_prediction(cx, cy, cyaw, ck, sp, goal)
+ t, x, y, yaw, v = do_simulation(cx, cy, cyaw, ck, sp, goal)
if show_animation: # pragma: no cover
plt.close()
@@ -271,6 +292,13 @@ def main():
plt.xlabel("x[m]")
plt.ylabel("y[m]")
plt.legend()
+ plt.subplots(1)
+
+ plt.plot(t, np.array(v)*3.6, label="speed")
+ plt.grid(True)
+ plt.xlabel("Time [sec]")
+ plt.ylabel("Speed [m/s]")
+ plt.legend()
plt.subplots(1)
plt.plot(s, [np.rad2deg(iyaw) for iyaw in cyaw], "-r", label="yaw")
diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py
index f977cdc2a1..3c066917ff 100644
--- a/PathTracking/lqr_steer_control/lqr_steer_control.py
+++ b/PathTracking/lqr_steer_control/lqr_steer_control.py
@@ -10,13 +10,11 @@
import math
import numpy as np
import sys
-sys.path.append("../../PathPlanning/CubicSpline/")
-
-try:
- import cubic_spline_planner
-except:
- raise
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
+from PathPlanning.CubicSpline import cubic_spline_planner
Kp = 1.0 # speed proportional gain
@@ -26,7 +24,7 @@
# parameters
dt = 0.1 # time tick[s]
-L = 0.5 # Wheel base of the vehicle [m]
+L = 0.5 # Wheelbase of the vehicle [m]
max_steer = np.deg2rad(45.0) # maximum steering angle[rad]
show_animation = True
@@ -57,14 +55,14 @@ def update(state, a, delta):
return state
-def PIDControl(target, current):
+def pid_control(target, current):
a = Kp * (target - current)
return a
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def solve_DARE(A, B, Q, R):
@@ -72,10 +70,11 @@ def solve_DARE(A, B, Q, R):
solve a discrete time_Algebraic Riccati equation (DARE)
"""
X = Q
- maxiter = 150
+ Xn = Q
+ max_iter = 150
eps = 0.01
- for i in range(maxiter):
+ for i in range(max_iter):
Xn = A.T @ X @ A - A.T @ X @ B @ \
la.inv(R + B.T @ X @ B) @ B.T @ X @ A + Q
if (abs(Xn - X)).max() < eps:
@@ -180,7 +179,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
dl, target_ind, e, e_th = lqr_steering_control(
state, cx, cy, cyaw, ck, e, e_th)
- ai = PIDControl(speed_profile[target_ind], state.v)
+ ai = pid_control(speed_profile[target_ind], state.v)
state = update(state, ai, dl)
if abs(state.v) <= stop_speed:
@@ -191,7 +190,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
# check goal
dx = state.x - goal[0]
dy = state.y - goal[1]
- if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
+ if math.hypot(dx, dy) <= goal_dis:
print("Goal")
break
@@ -203,6 +202,10 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
if target_ind % 1 == 0 and show_animation:
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(cx, cy, "-r", label="course")
plt.plot(x, y, "ob", label="trajectory")
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
diff --git a/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb b/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb
deleted file mode 100644
index 6e3fe45be3..0000000000
--- a/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb
+++ /dev/null
@@ -1,333 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Model predictive speed and steering control\n",
- "\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\n",
- "\n",
- "code:\n",
- "\n",
- "[PythonRobotics/model\\_predictive\\_speed\\_and\\_steer\\_control\\.py at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py)\n",
- "\n",
- "This is a path tracking simulation using model predictive control (MPC).\n",
- "\n",
- "The MPC controller controls vehicle speed and steering base on linealized model.\n",
- "\n",
- "This code uses cvxpy as an optimization modeling tool.\n",
- "\n",
- "- [Welcome to CVXPY 1\\.0 — CVXPY 1\\.0\\.6 documentation](http://www.cvxpy.org/)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### MPC modeling\n",
- "\n",
- "State vector is:\n",
- "\n",
- "$$ z = [x, y, v,\\phi]$$\n",
- "\n",
- "x: x-position, y:y-position, v:velocity, φ: yaw angle\n",
- "\n",
- "Input vector is:\n",
- "\n",
- "$$ u = [a, \\delta]$$\n",
- "\n",
- "a: accellation, δ: steering angle\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "The MPC cotroller minimize this cost function for path tracking:\n",
- "\n",
- "$$min\\ Q_f(z_{T,ref}-z_{T})^2+Q\\Sigma({z_{t,ref}-z_{t}})^2+R\\Sigma{u_t}^2+R_d\\Sigma({u_{t+1}-u_{t}})^2$$\n",
- "\n",
- "z_ref come from target path and speed."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "subject to:\n",
- "\n",
- "- Linearlied vehicle model\n",
- "\n",
- "$$z_{t+1}=Az_t+Bu+C$$\n",
- "\n",
- "- Maximum steering speed\n",
- "\n",
- "$$|u_{t+1}-u_{t}| math.pi):
- angle = angle - 2.0 * math.pi
-
- while(angle < -math.pi):
- angle = angle + 2.0 * math.pi
-
- return angle
+ return angle_mod(angle)
def get_linear_model_matrix(v, phi, delta):
@@ -175,9 +169,9 @@ def update_state(state, a, delta):
state.yaw = state.yaw + state.v / WB * math.tan(delta) * DT
state.v = state.v + a * DT
- if state. v > MAX_SPEED:
+ if state.v > MAX_SPEED:
state.v = MAX_SPEED
- elif state. v < MIN_SPEED:
+ elif state.v < MIN_SPEED:
state.v = MIN_SPEED
return state
@@ -228,8 +222,9 @@ def predict_motion(x0, oa, od, xref):
def iterative_linear_mpc_control(xref, x0, dref, oa, od):
"""
- MPC contorl with updating operational point iteraitvely
+ MPC control with updating operational point iteratively
"""
+ ox, oy, oyaw, ov = None, None, None, None
if oa is None or od is None:
oa = [0.0] * T
@@ -272,7 +267,7 @@ def linear_mpc_control(xref, xbar, x0, dref):
A, B, C = get_linear_model_matrix(
xbar[2, t], xbar[3, t], dref[0, t])
- constraints += [x[:, t + 1] == A * x[:, t] + B * u[:, t] + C]
+ constraints += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C]
if t < (T - 1):
cost += cvxpy.quad_form(u[:, t + 1] - u[:, t], Rd)
@@ -288,7 +283,7 @@ def linear_mpc_control(xref, xbar, x0, dref):
constraints += [cvxpy.abs(u[1, :]) <= MAX_STEER]
prob = cvxpy.Problem(cvxpy.Minimize(cost), constraints)
- prob.solve(solver=cvxpy.ECOS, verbose=False)
+ prob.solve(solver=cvxpy.CLARABEL, verbose=False)
if prob.status == cvxpy.OPTIMAL or prob.status == cvxpy.OPTIMAL_INACCURATE:
ox = get_nparray_from_matrix(x.value[0, :])
@@ -348,7 +343,7 @@ def check_goal(state, goal, tind, nind):
# check goal
dx = state.x - goal[0]
dy = state.y - goal[1]
- d = math.sqrt(dx ** 2 + dy ** 2)
+ d = math.hypot(dx, dy)
isgoal = (d <= GOAL_DIS)
@@ -409,10 +404,11 @@ def do_simulation(cx, cy, cyaw, ck, sp, dl, initial_state):
oa, odelta, ox, oy, oyaw, ov = iterative_linear_mpc_control(
xref, x0, dref, oa, odelta)
+ di, ai = 0.0, 0.0
if odelta is not None:
di, ai = odelta[0], oa[0]
+ state = update_state(state, ai, di)
- state = update_state(state, ai, di)
time = time + DT
x.append(state.x)
@@ -429,6 +425,9 @@ def do_simulation(cx, cy, cyaw, ck, sp, dl, initial_state):
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
if ox is not None:
plt.plot(ox, oy, "xr", label="MPC")
plt.plot(cx, cy, "-r", label="course")
@@ -548,6 +547,7 @@ def get_switch_back_course(dl):
def main():
print(__file__ + " start!!")
+ start = time.time()
dl = 1.0 # course tick
# cx, cy, cyaw, ck = get_straight_course(dl)
@@ -563,6 +563,9 @@ def main():
t, x, y, yaw, v, d, a = do_simulation(
cx, cy, cyaw, ck, sp, dl, initial_state)
+ elapsed_time = time.time() - start
+ print(f"calc time:{elapsed_time:.6f} [sec]")
+
if show_animation: # pragma: no cover
plt.close("all")
plt.subplots()
@@ -585,6 +588,7 @@ def main():
def main2():
print(__file__ + " start!!")
+ start = time.time()
dl = 1.0 # course tick
cx, cy, cyaw, ck = get_straight_course3(dl)
@@ -596,6 +600,9 @@ def main2():
t, x, y, yaw, v, d, a = do_simulation(
cx, cy, cyaw, ck, sp, dl, initial_state)
+ elapsed_time = time.time() - start
+ print(f"calc time:{elapsed_time:.6f} [sec]")
+
if show_animation: # pragma: no cover
plt.close("all")
plt.subplots()
diff --git a/PathTracking/move_to_pose/__init__.py b/PathTracking/move_to_pose/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/PathTracking/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py
index 0814ef62ef..faf1264953 100644
--- a/PathTracking/move_to_pose/move_to_pose.py
+++ b/PathTracking/move_to_pose/move_to_pose.py
@@ -3,7 +3,9 @@
Move to specified pose
Author: Daniel Ingram (daniel-s-ingram)
- Atsushi Sakai(@Atsushi_twi)
+ Atsushi Sakai (@Atsushi_twi)
+ Seied Muhammad Yazdian (@Muhammad-Yazdian)
+ Wang Zheng (@Aglargil)
P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7
@@ -11,26 +13,100 @@
import matplotlib.pyplot as plt
import numpy as np
+import sys
+import pathlib
+
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
from random import random
+
+class PathFinderController:
+ """
+ Constructs an instantiate of the PathFinderController for navigating a
+ 3-DOF wheeled robot on a 2D plane
+
+ Parameters
+ ----------
+ Kp_rho : The linear velocity gain to translate the robot along a line
+ towards the goal
+ Kp_alpha : The angular velocity gain to rotate the robot towards the goal
+ Kp_beta : The offset angular velocity gain accounting for smooth merging to
+ the goal angle (i.e., it helps the robot heading to be parallel
+ to the target angle.)
+ """
+
+ def __init__(self, Kp_rho, Kp_alpha, Kp_beta):
+ self.Kp_rho = Kp_rho
+ self.Kp_alpha = Kp_alpha
+ self.Kp_beta = Kp_beta
+
+ def calc_control_command(self, x_diff, y_diff, theta, theta_goal):
+ """
+ Returns the control command for the linear and angular velocities as
+ well as the distance to goal
+
+ Parameters
+ ----------
+ x_diff : The position of target with respect to current robot position
+ in x direction
+ y_diff : The position of target with respect to current robot position
+ in y direction
+ theta : The current heading angle of robot with respect to x axis
+ theta_goal: The target angle of robot with respect to x axis
+
+ Returns
+ -------
+ rho : The distance between the robot and the goal position
+ v : Command linear velocity
+ w : Command angular velocity
+ """
+
+ # Description of local variables:
+ # - alpha is the angle to the goal relative to the heading of the robot
+ # - beta is the angle between the robot's position and the goal
+ # position plus the goal angle
+ # - Kp_rho*rho and Kp_alpha*alpha drive the robot along a line towards
+ # the goal
+ # - Kp_beta*beta rotates the line so that it is parallel to the goal
+ # angle
+ #
+ # Note:
+ # we restrict alpha and beta (angle differences) to the range
+ # [-pi, pi] to prevent unstable behavior e.g. difference going
+ # from 0 rad to 2*pi rad with slight turn
+
+ # The velocity v always has a constant sign which depends on the initial value of α.
+ rho = np.hypot(x_diff, y_diff)
+ v = self.Kp_rho * rho
+
+ alpha = angle_mod(np.arctan2(y_diff, x_diff) - theta)
+ beta = angle_mod(theta_goal - theta - alpha)
+ if alpha > np.pi / 2 or alpha < -np.pi / 2:
+ # recalculate alpha to make alpha in the range of [-pi/2, pi/2]
+ alpha = angle_mod(np.arctan2(-y_diff, -x_diff) - theta)
+ beta = angle_mod(theta_goal - theta - alpha)
+ w = self.Kp_alpha * alpha - self.Kp_beta * beta
+ v = -v
+ else:
+ w = self.Kp_alpha * alpha - self.Kp_beta * beta
+
+ return rho, v, w
+
+
# simulation parameters
-Kp_rho = 9
-Kp_alpha = 15
-Kp_beta = -3
+controller = PathFinderController(9, 15, 3)
dt = 0.01
+MAX_SIM_TIME = 5 # seconds, robot will stop moving when time exceeds this value
+
+# Robot specifications
+MAX_LINEAR_SPEED = 15
+MAX_ANGULAR_SPEED = 7
show_animation = True
def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal):
- """
- rho is the distance between the robot and the goal position
- alpha is the angle to the goal relative to the heading of the robot
- beta is the angle between the robot's position and the goal position plus the goal angle
-
- Kp_rho*rho and Kp_alpha*alpha drive the robot along a line towards the goal
- Kp_beta*beta rotates the line so that it is parallel to the goal angle
- """
x = x_start
y = y_start
theta = theta_start
@@ -38,30 +114,28 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal):
x_diff = x_goal - x
y_diff = y_goal - y
- x_traj, y_traj = [], []
+ x_traj, y_traj, v_traj, w_traj = [x], [y], [0], [0]
- rho = np.sqrt(x_diff**2 + y_diff**2)
- while rho > 0.001:
+ rho = np.hypot(x_diff, y_diff)
+ t = 0
+ while rho > 0.001 and t < MAX_SIM_TIME:
+ t += dt
x_traj.append(x)
y_traj.append(y)
x_diff = x_goal - x
y_diff = y_goal - y
- # Restrict alpha and beta (angle differences) to the range
- # [-pi, pi] to prevent unstable behavior e.g. difference going
- # from 0 rad to 2*pi rad with slight turn
+ rho, v, w = controller.calc_control_command(x_diff, y_diff, theta, theta_goal)
- rho = np.sqrt(x_diff**2 + y_diff**2)
- alpha = (np.arctan2(y_diff, x_diff)
- - theta + np.pi) % (2 * np.pi) - np.pi
- beta = (theta_goal - theta - alpha + np.pi) % (2 * np.pi) - np.pi
+ if abs(v) > MAX_LINEAR_SPEED:
+ v = np.sign(v) * MAX_LINEAR_SPEED
- v = Kp_rho * rho
- w = Kp_alpha * alpha + Kp_beta * beta
+ if abs(w) > MAX_ANGULAR_SPEED:
+ w = np.sign(w) * MAX_ANGULAR_SPEED
- if alpha > np.pi / 2 or alpha < -np.pi / 2:
- v = -v
+ v_traj.append(v)
+ w_traj.append(w)
theta = theta + w * dt
x = x + v * np.cos(theta) * dt
@@ -69,12 +143,26 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal):
if show_animation: # pragma: no cover
plt.cla()
- plt.arrow(x_start, y_start, np.cos(theta_start),
- np.sin(theta_start), color='r', width=0.1)
- plt.arrow(x_goal, y_goal, np.cos(theta_goal),
- np.sin(theta_goal), color='g', width=0.1)
+ plt.arrow(
+ x_start,
+ y_start,
+ np.cos(theta_start),
+ np.sin(theta_start),
+ color="r",
+ width=0.1,
+ )
+ plt.arrow(
+ x_goal,
+ y_goal,
+ np.cos(theta_goal),
+ np.sin(theta_goal),
+ color="g",
+ width=0.1,
+ )
plot_vehicle(x, y, theta, x_traj, y_traj)
+ return x_traj, y_traj, v_traj, w_traj
+
def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover
# Corners of triangular vehicle when pointing to the right (0 radians)
@@ -87,11 +175,16 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover
p2 = np.matmul(T, p2_i)
p3 = np.matmul(T, p3_i)
- plt.plot([p1[0], p2[0]], [p1[1], p2[1]], 'k-')
- plt.plot([p2[0], p3[0]], [p2[1], p3[1]], 'k-')
- plt.plot([p3[0], p1[0]], [p3[1], p1[1]], 'k-')
+ plt.plot([p1[0], p2[0]], [p1[1], p2[1]], "k-")
+ plt.plot([p2[0], p3[0]], [p2[1], p3[1]], "k-")
+ plt.plot([p3[0], p1[0]], [p3[1], p1[1]], "k-")
+
+ plt.plot(x_traj, y_traj, "b--")
- plt.plot(x_traj, y_traj, 'b--')
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ "key_release_event", lambda event: [exit(0) if event.key == "escape" else None]
+ )
plt.xlim(0, 20)
plt.ylim(0, 20)
@@ -100,28 +193,31 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover
def transformation_matrix(x, y, theta):
- return np.array([
- [np.cos(theta), -np.sin(theta), x],
- [np.sin(theta), np.cos(theta), y],
- [0, 0, 1]
- ])
+ return np.array(
+ [
+ [np.cos(theta), -np.sin(theta), x],
+ [np.sin(theta), np.cos(theta), y],
+ [0, 0, 1],
+ ]
+ )
def main():
-
for i in range(5):
- x_start = 20 * random()
- y_start = 20 * random()
- theta_start = 2 * np.pi * random() - np.pi
+ x_start = 20.0 * random()
+ y_start = 20.0 * random()
+ theta_start: float = 2 * np.pi * random() - np.pi
x_goal = 20 * random()
y_goal = 20 * random()
theta_goal = 2 * np.pi * random() - np.pi
- print("Initial x: %.2f m\nInitial y: %.2f m\nInitial theta: %.2f rad\n" %
- (x_start, y_start, theta_start))
- print("Goal x: %.2f m\nGoal y: %.2f m\nGoal theta: %.2f rad\n" %
- (x_goal, y_goal, theta_goal))
+ print(
+ f"Initial x: {round(x_start, 2)} m\nInitial y: {round(y_start, 2)} m\nInitial theta: {round(theta_start, 2)} rad\n"
+ )
+ print(
+ f"Goal x: {round(x_goal, 2)} m\nGoal y: {round(y_goal, 2)} m\nGoal theta: {round(theta_goal, 2)} rad\n"
+ )
move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal)
-if __name__ == '__main__':
+if __name__ == "__main__":
main()
diff --git a/PathTracking/move_to_pose/move_to_pose_robot.py b/PathTracking/move_to_pose/move_to_pose_robot.py
new file mode 100644
index 0000000000..fe9f0d06b3
--- /dev/null
+++ b/PathTracking/move_to_pose/move_to_pose_robot.py
@@ -0,0 +1,240 @@
+"""
+
+Move to specified pose (with Robot class)
+
+Author: Daniel Ingram (daniel-s-ingram)
+ Atsushi Sakai (@Atsushi_twi)
+ Seied Muhammad Yazdian (@Muhammad-Yazdian)
+
+P.I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7
+
+"""
+
+import matplotlib.pyplot as plt
+import numpy as np
+import copy
+from move_to_pose import PathFinderController
+
+# Simulation parameters
+TIME_DURATION = 1000
+TIME_STEP = 0.01
+AT_TARGET_ACCEPTANCE_THRESHOLD = 0.01
+SHOW_ANIMATION = True
+PLOT_WINDOW_SIZE_X = 20
+PLOT_WINDOW_SIZE_Y = 20
+PLOT_FONT_SIZE = 8
+
+simulation_running = True
+all_robots_are_at_target = False
+
+
+class Pose:
+ """2D pose"""
+
+ def __init__(self, x, y, theta):
+ self.x = x
+ self.y = y
+ self.theta = theta
+
+
+class Robot:
+ """
+ Constructs an instantiate of the 3-DOF wheeled Robot navigating on a
+ 2D plane
+
+ Parameters
+ ----------
+ name : (string)
+ The name of the robot
+ color : (string)
+ The color of the robot
+ max_linear_speed : (float)
+ The maximum linear speed that the robot can go
+ max_angular_speed : (float)
+ The maximum angular speed that the robot can rotate about its vertical
+ axis
+ path_finder_controller : (PathFinderController)
+ A configurable controller to finds the path and calculates command
+ linear and angular velocities.
+ """
+
+ def __init__(self, name, color, max_linear_speed, max_angular_speed,
+ path_finder_controller):
+ self.name = name
+ self.color = color
+ self.MAX_LINEAR_SPEED = max_linear_speed
+ self.MAX_ANGULAR_SPEED = max_angular_speed
+ self.path_finder_controller = path_finder_controller
+ self.x_traj = []
+ self.y_traj = []
+ self.pose = Pose(0, 0, 0)
+ self.pose_start = Pose(0, 0, 0)
+ self.pose_target = Pose(0, 0, 0)
+ self.is_at_target = False
+
+ def set_start_target_poses(self, pose_start, pose_target):
+ """
+ Sets the start and target positions of the robot
+
+ Parameters
+ ----------
+ pose_start : (Pose)
+ Start position of the robot (see the Pose class)
+ pose_target : (Pose)
+ Target position of the robot (see the Pose class)
+ """
+ self.pose_start = copy.copy(pose_start)
+ self.pose_target = pose_target
+ self.pose = pose_start
+
+ def move(self, dt):
+ """
+ Moves the robot for one time step increment
+
+ Parameters
+ ----------
+ dt : (float)
+ time step
+ """
+ self.x_traj.append(self.pose.x)
+ self.y_traj.append(self.pose.y)
+
+ rho, linear_velocity, angular_velocity = \
+ self.path_finder_controller.calc_control_command(
+ self.pose_target.x - self.pose.x,
+ self.pose_target.y - self.pose.y,
+ self.pose.theta, self.pose_target.theta)
+
+ if rho < AT_TARGET_ACCEPTANCE_THRESHOLD:
+ self.is_at_target = True
+
+ if abs(linear_velocity) > self.MAX_LINEAR_SPEED:
+ linear_velocity = (np.sign(linear_velocity)
+ * self.MAX_LINEAR_SPEED)
+
+ if abs(angular_velocity) > self.MAX_ANGULAR_SPEED:
+ angular_velocity = (np.sign(angular_velocity)
+ * self.MAX_ANGULAR_SPEED)
+
+ self.pose.theta = self.pose.theta + angular_velocity * dt
+ self.pose.x = self.pose.x + linear_velocity * \
+ np.cos(self.pose.theta) * dt
+ self.pose.y = self.pose.y + linear_velocity * \
+ np.sin(self.pose.theta) * dt
+
+
+def run_simulation(robots):
+ """Simulates all robots simultaneously"""
+ global all_robots_are_at_target
+ global simulation_running
+
+ robot_names = []
+ for instance in robots:
+ robot_names.append(instance.name)
+
+ time = 0
+ while simulation_running and time < TIME_DURATION:
+ time += TIME_STEP
+ robots_are_at_target = []
+
+ for instance in robots:
+ if not instance.is_at_target:
+ instance.move(TIME_STEP)
+ robots_are_at_target.append(instance.is_at_target)
+
+ if all(robots_are_at_target):
+ simulation_running = False
+
+ if SHOW_ANIMATION:
+ plt.cla()
+ plt.xlim(0, PLOT_WINDOW_SIZE_X)
+ plt.ylim(0, PLOT_WINDOW_SIZE_Y)
+
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+
+ plt.text(0.3, PLOT_WINDOW_SIZE_Y - 1,
+ 'Time: {:.2f}'.format(time),
+ fontsize=PLOT_FONT_SIZE)
+
+ plt.text(0.3, PLOT_WINDOW_SIZE_Y - 2,
+ 'Reached target: {} = '.format(robot_names)
+ + str(robots_are_at_target),
+ fontsize=PLOT_FONT_SIZE)
+
+ for instance in robots:
+ plt.arrow(instance.pose_start.x,
+ instance.pose_start.y,
+ np.cos(instance.pose_start.theta),
+ np.sin(instance.pose_start.theta),
+ color='r',
+ width=0.1)
+ plt.arrow(instance.pose_target.x,
+ instance.pose_target.y,
+ np.cos(instance.pose_target.theta),
+ np.sin(instance.pose_target.theta),
+ color='g',
+ width=0.1)
+ plot_vehicle(instance.pose.x,
+ instance.pose.y,
+ instance.pose.theta,
+ instance.x_traj,
+ instance.y_traj, instance.color)
+
+ plt.pause(TIME_STEP)
+
+
+def plot_vehicle(x, y, theta, x_traj, y_traj, color):
+ # Corners of triangular vehicle when pointing to the right (0 radians)
+ p1_i = np.array([0.5, 0, 1]).T
+ p2_i = np.array([-0.5, 0.25, 1]).T
+ p3_i = np.array([-0.5, -0.25, 1]).T
+
+ T = transformation_matrix(x, y, theta)
+ p1 = T @ p1_i
+ p2 = T @ p2_i
+ p3 = T @ p3_i
+
+ plt.plot([p1[0], p2[0]], [p1[1], p2[1]], color+'-')
+ plt.plot([p2[0], p3[0]], [p2[1], p3[1]], color+'-')
+ plt.plot([p3[0], p1[0]], [p3[1], p1[1]], color+'-')
+
+ plt.plot(x_traj, y_traj, color+'--')
+
+
+def transformation_matrix(x, y, theta):
+ return np.array([
+ [np.cos(theta), -np.sin(theta), x],
+ [np.sin(theta), np.cos(theta), y],
+ [0, 0, 1]
+ ])
+
+
+def main():
+ pose_target = Pose(15, 15, -1)
+
+ pose_start_1 = Pose(5, 2, 0)
+ pose_start_2 = Pose(5, 2, 0)
+ pose_start_3 = Pose(5, 2, 0)
+
+ controller_1 = PathFinderController(5, 8, 2)
+ controller_2 = PathFinderController(5, 16, 4)
+ controller_3 = PathFinderController(10, 25, 6)
+
+ robot_1 = Robot("Yellow Robot", "y", 12, 5, controller_1)
+ robot_2 = Robot("Black Robot", "k", 16, 5, controller_2)
+ robot_3 = Robot("Blue Robot", "b", 20, 5, controller_3)
+
+ robot_1.set_start_target_poses(pose_start_1, pose_target)
+ robot_2.set_start_target_poses(pose_start_2, pose_target)
+ robot_3.set_start_target_poses(pose_start_3, pose_target)
+
+ robots: list[Robot] = [robot_1, robot_2, robot_3]
+
+ run_simulation(robots)
+
+
+if __name__ == '__main__':
+ main()
diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py
index 38a84affce..48453927ab 100644
--- a/PathTracking/pure_pursuit/pure_pursuit.py
+++ b/PathTracking/pure_pursuit/pure_pursuit.py
@@ -1,120 +1,155 @@
"""
-Path tracking simulation with pure pursuit steering control and PID speed control.
+Path tracking simulation with pure pursuit steering and PID speed control.
author: Atsushi Sakai (@Atsushi_twi)
+ Guillaume Jacquenot (@Gjacquenot)
"""
import numpy as np
import math
import matplotlib.pyplot as plt
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
+# Parameters
k = 0.1 # look forward gain
-Lfc = 2.0 # look-ahead distance
+Lfc = 2.0 # [m] look-ahead distance
Kp = 1.0 # speed proportional gain
-dt = 0.1 # [s]
-L = 2.9 # [m] wheel base of vehicle
+dt = 0.1 # [s] time tick
+WB = 2.9 # [m] wheel base of vehicle
-old_nearest_point_index = None
-show_animation = True
+# Vehicle parameters
+LENGTH = WB + 1.0 # Vehicle length
+WIDTH = 2.0 # Vehicle width
+WHEEL_LEN = 0.6 # Wheel length
+WHEEL_WIDTH = 0.2 # Wheel width
+MAX_STEER = math.pi / 4 # Maximum steering angle [rad]
-class State:
+show_animation = True
+pause_simulation = False # Flag for pause simulation
+is_reverse_mode = False # Flag for reverse driving mode
- def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
+class State:
+ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0, is_reverse=False):
self.x = x
self.y = y
self.yaw = yaw
self.v = v
- self.rear_x = self.x - ((L / 2) * math.cos(self.yaw))
- self.rear_y = self.y - ((L / 2) * math.sin(self.yaw))
+ self.direction = -1 if is_reverse else 1 # Direction based on reverse flag
+ self.rear_x = self.x - self.direction * ((WB / 2) * math.cos(self.yaw))
+ self.rear_y = self.y - self.direction * ((WB / 2) * math.sin(self.yaw))
+
+ def update(self, a, delta):
+ self.x += self.v * math.cos(self.yaw) * dt
+ self.y += self.v * math.sin(self.yaw) * dt
+ self.yaw += self.direction * self.v / WB * math.tan(delta) * dt
+ self.yaw = angle_mod(self.yaw)
+ self.v += a * dt
+ self.rear_x = self.x - self.direction * ((WB / 2) * math.cos(self.yaw))
+ self.rear_y = self.y - self.direction * ((WB / 2) * math.sin(self.yaw))
+
+ def calc_distance(self, point_x, point_y):
+ dx = self.rear_x - point_x
+ dy = self.rear_y - point_y
+ return math.hypot(dx, dy)
+
+
+class States:
+
+ def __init__(self):
+ self.x = []
+ self.y = []
+ self.yaw = []
+ self.v = []
+ self.direction = []
+ self.t = []
+
+ def append(self, t, state):
+ self.x.append(state.x)
+ self.y.append(state.y)
+ self.yaw.append(state.yaw)
+ self.v.append(state.v)
+ self.direction.append(state.direction)
+ self.t.append(t)
+
+
+def proportional_control(target, current):
+ a = Kp * (target - current)
+ return a
-def update(state, a, delta):
- state.x = state.x + state.v * math.cos(state.yaw) * dt
- state.y = state.y + state.v * math.sin(state.yaw) * dt
- state.yaw = state.yaw + state.v / L * math.tan(delta) * dt
- state.v = state.v + a * dt
- state.rear_x = state.x - ((L / 2) * math.cos(state.yaw))
- state.rear_y = state.y - ((L / 2) * math.sin(state.yaw))
+class TargetCourse:
- return state
+ def __init__(self, cx, cy):
+ self.cx = cx
+ self.cy = cy
+ self.old_nearest_point_index = None
+ def search_target_index(self, state):
-def PIDControl(target, current):
- a = Kp * (target - current)
+ # To speed up nearest point search, doing it at only first time.
+ if self.old_nearest_point_index is None:
+ # search nearest point index
+ dx = [state.rear_x - icx for icx in self.cx]
+ dy = [state.rear_y - icy for icy in self.cy]
+ d = np.hypot(dx, dy)
+ ind = np.argmin(d)
+ self.old_nearest_point_index = ind
+ else:
+ ind = self.old_nearest_point_index
+ distance_this_index = state.calc_distance(self.cx[ind],
+ self.cy[ind])
+ while True:
+ distance_next_index = state.calc_distance(self.cx[ind + 1],
+ self.cy[ind + 1])
+ if distance_this_index < distance_next_index:
+ break
+ ind = ind + 1 if (ind + 1) < len(self.cx) else ind
+ distance_this_index = distance_next_index
+ self.old_nearest_point_index = ind
- return a
+ Lf = k * state.v + Lfc # update look ahead distance
+
+ # search look ahead target point index
+ while Lf > state.calc_distance(self.cx[ind], self.cy[ind]):
+ if (ind + 1) >= len(self.cx):
+ break # not exceed goal
+ ind += 1
+ return ind, Lf
-def pure_pursuit_control(state, cx, cy, pind):
- ind = calc_target_index(state, cx, cy)
+def pure_pursuit_steer_control(state, trajectory, pind):
+ ind, Lf = trajectory.search_target_index(state)
if pind >= ind:
ind = pind
- if ind < len(cx):
- tx = cx[ind]
- ty = cy[ind]
+ if ind < len(trajectory.cx):
+ tx = trajectory.cx[ind]
+ ty = trajectory.cy[ind]
else:
- tx = cx[-1]
- ty = cy[-1]
- ind = len(cx) - 1
+ tx = trajectory.cx[-1]
+ ty = trajectory.cy[-1]
+ ind = len(trajectory.cx) - 1
alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw
- Lf = k * state.v + Lfc
+ # Reverse steering angle when reversing
+ delta = state.direction * math.atan2(2.0 * WB * math.sin(alpha) / Lf, 1.0)
- delta = math.atan2(2.0 * L * math.sin(alpha) / Lf, 1.0)
+ # Limit steering angle to max value
+ delta = np.clip(delta, -MAX_STEER, MAX_STEER)
return delta, ind
-def calc_distance(state, point_x, point_y):
-
- dx = state.rear_x - point_x
- dy = state.rear_y - point_y
- return math.sqrt(dx ** 2 + dy ** 2)
-
-
-def calc_target_index(state, cx, cy):
-
- global old_nearest_point_index
-
- if old_nearest_point_index is None:
- # search nearest point index
- dx = [state.rear_x - icx for icx in cx]
- dy = [state.rear_y - icy for icy in cy]
- d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)]
- ind = d.index(min(d))
- old_nearest_point_index = ind
- else:
- ind = old_nearest_point_index
- distance_this_index = calc_distance(state, cx[ind], cy[ind])
- while True:
- ind = ind + 1 if (ind + 1) < len(cx) else ind
- distance_next_index = calc_distance(state, cx[ind], cy[ind])
- if distance_this_index < distance_next_index:
- break
- distance_this_index = distance_next_index
- old_nearest_point_index = ind
-
- L = 0.0
-
- Lf = k * state.v + Lfc
-
- # search look ahead target point index
- while Lf > L and (ind + 1) < len(cx):
- dx = cx[ind] - state.rear_x
- dy = cy[ind] - state.rear_y
- L = math.sqrt(dx ** 2 + dy ** 2)
- ind += 1
-
- return ind
-
def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
"""
@@ -122,17 +157,118 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
"""
if not isinstance(x, float):
- for (ix, iy, iyaw) in zip(x, y, yaw):
+ for ix, iy, iyaw in zip(x, y, yaw):
plot_arrow(ix, iy, iyaw)
else:
plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw),
fc=fc, ec=ec, head_width=width, head_length=width)
plt.plot(x, y)
+def plot_vehicle(x, y, yaw, steer=0.0, color='blue', is_reverse=False):
+ """
+ Plot vehicle model with four wheels
+ Args:
+ x, y: Vehicle center position
+ yaw: Vehicle heading angle
+ steer: Steering angle
+ color: Vehicle color
+ is_reverse: Flag for reverse mode
+ """
+ # Adjust heading angle in reverse mode
+ if is_reverse:
+ yaw = angle_mod(yaw + math.pi) # Rotate heading by 180 degrees
+ steer = -steer # Reverse steering direction
+
+ def plot_wheel(x, y, yaw, steer=0.0, color=color):
+ """Plot single wheel"""
+ wheel = np.array([
+ [-WHEEL_LEN/2, WHEEL_WIDTH/2],
+ [WHEEL_LEN/2, WHEEL_WIDTH/2],
+ [WHEEL_LEN/2, -WHEEL_WIDTH/2],
+ [-WHEEL_LEN/2, -WHEEL_WIDTH/2],
+ [-WHEEL_LEN/2, WHEEL_WIDTH/2]
+ ])
+
+ # Rotate wheel if steering
+ if steer != 0:
+ c, s = np.cos(steer), np.sin(steer)
+ rot_steer = np.array([[c, -s], [s, c]])
+ wheel = wheel @ rot_steer.T
+
+ # Apply vehicle heading rotation
+ c, s = np.cos(yaw), np.sin(yaw)
+ rot_yaw = np.array([[c, -s], [s, c]])
+ wheel = wheel @ rot_yaw.T
+
+ # Translate to position
+ wheel[:, 0] += x
+ wheel[:, 1] += y
+
+ # Plot wheel with color
+ plt.plot(wheel[:, 0], wheel[:, 1], color=color)
+
+ # Calculate vehicle body corners
+ corners = np.array([
+ [-LENGTH/2, WIDTH/2],
+ [LENGTH/2, WIDTH/2],
+ [LENGTH/2, -WIDTH/2],
+ [-LENGTH/2, -WIDTH/2],
+ [-LENGTH/2, WIDTH/2]
+ ])
+
+ # Rotation matrix
+ c, s = np.cos(yaw), np.sin(yaw)
+ Rot = np.array([[c, -s], [s, c]])
+
+ # Rotate and translate vehicle body
+ rotated = corners @ Rot.T
+ rotated[:, 0] += x
+ rotated[:, 1] += y
+
+ # Plot vehicle body
+ plt.plot(rotated[:, 0], rotated[:, 1], color=color)
+
+ # Plot wheels (darker color for front wheels)
+ front_color = 'darkblue'
+ rear_color = color
+
+ # Plot four wheels
+ # Front left
+ plot_wheel(x + LENGTH/4 * c - WIDTH/2 * s,
+ y + LENGTH/4 * s + WIDTH/2 * c,
+ yaw, steer, front_color)
+ # Front right
+ plot_wheel(x + LENGTH/4 * c + WIDTH/2 * s,
+ y + LENGTH/4 * s - WIDTH/2 * c,
+ yaw, steer, front_color)
+ # Rear left
+ plot_wheel(x - LENGTH/4 * c - WIDTH/2 * s,
+ y - LENGTH/4 * s + WIDTH/2 * c,
+ yaw, color=rear_color)
+ # Rear right
+ plot_wheel(x - LENGTH/4 * c + WIDTH/2 * s,
+ y - LENGTH/4 * s - WIDTH/2 * c,
+ yaw, color=rear_color)
+
+ # Add direction arrow
+ arrow_length = LENGTH/3
+ plt.arrow(x, y,
+ -arrow_length * math.cos(yaw) if is_reverse else arrow_length * math.cos(yaw),
+ -arrow_length * math.sin(yaw) if is_reverse else arrow_length * math.sin(yaw),
+ head_width=WIDTH/4, head_length=WIDTH/4,
+ fc='r', ec='r', alpha=0.5)
+
+# Keyboard event handler
+def on_key(event):
+ global pause_simulation
+ if event.key == ' ': # Space key
+ pause_simulation = not pause_simulation
+ elif event.key == 'escape':
+ exit(0)
def main():
# target course
- cx = np.arange(0, 50, 0.1)
+ cx = -1 * np.arange(0, 50, 0.5) if is_reverse_mode else np.arange(0, 50, 0.5)
cy = [math.sin(ix / 5.0) * ix / 2.0 for ix in cx]
target_speed = 10.0 / 3.6 # [m/s]
@@ -140,48 +276,60 @@ def main():
T = 100.0 # max simulation time
# initial state
- state = State(x=-0.0, y=-3.0, yaw=0.0, v=0.0)
+ state = State(x=-0.0, y=-3.0, yaw=math.pi if is_reverse_mode else 0.0, v=0.0, is_reverse=is_reverse_mode)
lastIndex = len(cx) - 1
time = 0.0
- x = [state.x]
- y = [state.y]
- yaw = [state.yaw]
- v = [state.v]
- t = [0.0]
- target_ind = calc_target_index(state, cx, cy)
+ states = States()
+ states.append(time, state)
+ target_course = TargetCourse(cx, cy)
+ target_ind, _ = target_course.search_target_index(state)
while T >= time and lastIndex > target_ind:
- ai = PIDControl(target_speed, state.v)
- di, target_ind = pure_pursuit_control(state, cx, cy, target_ind)
- state = update(state, ai, di)
- time = time + dt
+ # Calc control input
+ ai = proportional_control(target_speed, state.v)
+ di, target_ind = pure_pursuit_steer_control(
+ state, target_course, target_ind)
- x.append(state.x)
- y.append(state.y)
- yaw.append(state.yaw)
- v.append(state.v)
- t.append(time)
+ state.update(ai, di) # Control vehicle
+ time += dt
+ states.append(time, state)
if show_animation: # pragma: no cover
plt.cla()
- plot_arrow(state.x, state.y, state.yaw)
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event', on_key)
+ # Pass is_reverse parameter
+ plot_vehicle(state.x, state.y, state.yaw, di, is_reverse=is_reverse_mode)
plt.plot(cx, cy, "-r", label="course")
- plt.plot(x, y, "-b", label="trajectory")
+ plt.plot(states.x, states.y, "-b", label="trajectory")
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
plt.axis("equal")
plt.grid(True)
plt.title("Speed[km/h]:" + str(state.v * 3.6)[:4])
+ plt.legend() # Add legend display
+
+ # Add pause state display
+ if pause_simulation:
+ plt.text(0.02, 0.95, 'PAUSED', transform=plt.gca().transAxes,
+ bbox=dict(facecolor='red', alpha=0.5))
+
plt.pause(0.001)
+ # Handle pause state
+ while pause_simulation:
+ plt.pause(0.1) # Reduce CPU usage
+ if not plt.get_fignums(): # Check if window is closed
+ exit(0)
+
# Test
assert lastIndex >= target_ind, "Cannot goal"
if show_animation: # pragma: no cover
plt.cla()
plt.plot(cx, cy, ".r", label="course")
- plt.plot(x, y, "-b", label="trajectory")
+ plt.plot(states.x, states.y, "-b", label="trajectory")
plt.legend()
plt.xlabel("x[m]")
plt.ylabel("y[m]")
@@ -189,7 +337,7 @@ def main():
plt.grid(True)
plt.subplots(1)
- plt.plot(t, [iv * 3.6 for iv in v], "-r")
+ plt.plot(states.t, [iv * 3.6 for iv in states.v], "-r")
plt.xlabel("Time[s]")
plt.ylabel("Speed[km/h]")
plt.grid(True)
diff --git a/PathTracking/rear_wheel_feedback/Figure_2.png b/PathTracking/rear_wheel_feedback/Figure_2.png
deleted file mode 100644
index 66c99b1de8..0000000000
Binary files a/PathTracking/rear_wheel_feedback/Figure_2.png and /dev/null differ
diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py
deleted file mode 100644
index 285d9404e3..0000000000
--- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py
+++ /dev/null
@@ -1,239 +0,0 @@
-"""
-
-Path tracking simulation with rear wheel feedback steering control and PID speed control.
-
-author: Atsushi Sakai(@Atsushi_twi)
-
-"""
-import matplotlib.pyplot as plt
-import math
-import numpy as np
-import sys
-sys.path.append("../../PathPlanning/CubicSpline/")
-
-try:
- import cubic_spline_planner
-except:
- raise
-
-
-Kp = 1.0 # speed propotional gain
-# steering control parameter
-KTH = 1.0
-KE = 0.5
-
-dt = 0.1 # [s]
-L = 2.9 # [m]
-
-show_animation = True
-# show_animation = False
-
-
-class State:
-
- def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
- self.x = x
- self.y = y
- self.yaw = yaw
- self.v = v
-
-
-def update(state, a, delta):
-
- state.x = state.x + state.v * math.cos(state.yaw) * dt
- state.y = state.y + state.v * math.sin(state.yaw) * dt
- state.yaw = state.yaw + state.v / L * math.tan(delta) * dt
- state.v = state.v + a * dt
-
- return state
-
-
-def PIDControl(target, current):
- a = Kp * (target - current)
-
- return a
-
-
-def pi_2_pi(angle):
- while(angle > math.pi):
- angle = angle - 2.0 * math.pi
-
- while(angle < -math.pi):
- angle = angle + 2.0 * math.pi
-
- return angle
-
-
-def rear_wheel_feedback_control(state, cx, cy, cyaw, ck, preind):
- ind, e = calc_nearest_index(state, cx, cy, cyaw)
-
- k = ck[ind]
- v = state.v
- th_e = pi_2_pi(state.yaw - cyaw[ind])
-
- omega = v * k * math.cos(th_e) / (1.0 - k * e) - \
- KTH * abs(v) * th_e - KE * v * math.sin(th_e) * e / th_e
-
- if th_e == 0.0 or omega == 0.0:
- return 0.0, ind
-
- delta = math.atan2(L * omega / v, 1.0)
- # print(k, v, e, th_e, omega, delta)
-
- return delta, ind
-
-
-def calc_nearest_index(state, cx, cy, cyaw):
- dx = [state.x - icx for icx in cx]
- dy = [state.y - icy for icy in cy]
-
- d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)]
-
- mind = min(d)
-
- ind = d.index(mind)
-
- mind = math.sqrt(mind)
-
- dxl = cx[ind] - state.x
- dyl = cy[ind] - state.y
-
- angle = pi_2_pi(cyaw[ind] - math.atan2(dyl, dxl))
- if angle < 0:
- mind *= -1
-
- return ind, mind
-
-
-def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
-
- T = 500.0 # max simulation time
- goal_dis = 0.3
- stop_speed = 0.05
-
- state = State(x=-0.0, y=-0.0, yaw=0.0, v=0.0)
-
- time = 0.0
- x = [state.x]
- y = [state.y]
- yaw = [state.yaw]
- v = [state.v]
- t = [0.0]
- goal_flag = False
- target_ind = calc_nearest_index(state, cx, cy, cyaw)
-
- while T >= time:
- di, target_ind = rear_wheel_feedback_control(
- state, cx, cy, cyaw, ck, target_ind)
- ai = PIDControl(speed_profile[target_ind], state.v)
- state = update(state, ai, di)
-
- if abs(state.v) <= stop_speed:
- target_ind += 1
-
- time = time + dt
-
- # check goal
- dx = state.x - goal[0]
- dy = state.y - goal[1]
- if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
- print("Goal")
- goal_flag = True
- break
-
- x.append(state.x)
- y.append(state.y)
- yaw.append(state.yaw)
- v.append(state.v)
- t.append(time)
-
- if target_ind % 1 == 0 and show_animation:
- plt.cla()
- plt.plot(cx, cy, "-r", label="course")
- plt.plot(x, y, "ob", label="trajectory")
- plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
- plt.axis("equal")
- plt.grid(True)
- plt.title("speed[km/h]:" + str(round(state.v * 3.6, 2)) +
- ",target index:" + str(target_ind))
- plt.pause(0.0001)
-
- return t, x, y, yaw, v, goal_flag
-
-
-def calc_speed_profile(cx, cy, cyaw, target_speed):
-
- speed_profile = [target_speed] * len(cx)
-
- direction = 1.0
-
- # Set stop point
- for i in range(len(cx) - 1):
- dyaw = cyaw[i + 1] - cyaw[i]
- switch = math.pi / 4.0 <= dyaw < math.pi / 2.0
-
- if switch:
- direction *= -1
-
- if direction != 1.0:
- speed_profile[i] = - target_speed
- else:
- speed_profile[i] = target_speed
-
- if switch:
- speed_profile[i] = 0.0
-
- speed_profile[-1] = 0.0
-
- return speed_profile
-
-
-def main():
- print("rear wheel feedback tracking start!!")
- ax = [0.0, 6.0, 12.5, 5.0, 7.5, 3.0, -1.0]
- ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0]
- goal = [ax[-1], ay[-1]]
-
- cx, cy, cyaw, ck, s = cubic_spline_planner.calc_spline_course(
- ax, ay, ds=0.1)
- target_speed = 10.0 / 3.6
-
- sp = calc_speed_profile(cx, cy, cyaw, target_speed)
-
- t, x, y, yaw, v, goal_flag = closed_loop_prediction(
- cx, cy, cyaw, ck, sp, goal)
-
- # Test
- assert goal_flag, "Cannot goal"
-
- if show_animation: # pragma: no cover
- plt.close()
- plt.subplots(1)
- plt.plot(ax, ay, "xb", label="input")
- plt.plot(cx, cy, "-r", label="spline")
- plt.plot(x, y, "-g", label="tracking")
- plt.grid(True)
- plt.axis("equal")
- plt.xlabel("x[m]")
- plt.ylabel("y[m]")
- plt.legend()
-
- plt.subplots(1)
- plt.plot(s, [np.rad2deg(iyaw) for iyaw in cyaw], "-r", label="yaw")
- plt.grid(True)
- plt.legend()
- plt.xlabel("line length[m]")
- plt.ylabel("yaw angle[deg]")
-
- plt.subplots(1)
- plt.plot(s, ck, "-r", label="curvature")
- plt.grid(True)
- plt.legend()
- plt.xlabel("line length[m]")
- plt.ylabel("curvature [1/m]")
-
- plt.show()
-
-
-if __name__ == '__main__':
- main()
diff --git a/PathTracking/rear_wheel_feedback_control/rear_wheel_feedback_control.py b/PathTracking/rear_wheel_feedback_control/rear_wheel_feedback_control.py
new file mode 100644
index 0000000000..fd04fb6d17
--- /dev/null
+++ b/PathTracking/rear_wheel_feedback_control/rear_wheel_feedback_control.py
@@ -0,0 +1,234 @@
+"""
+
+Path tracking simulation with rear wheel feedback steering control and PID speed control.
+
+author: Atsushi Sakai(@Atsushi_twi)
+
+"""
+import matplotlib.pyplot as plt
+import math
+import numpy as np
+import sys
+import pathlib
+from scipy import interpolate
+from scipy import optimize
+
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
+
+Kp = 1.0 # speed proportional gain
+# steering control parameter
+KTH = 1.0
+KE = 0.5
+
+dt = 0.1 # [s]
+L = 2.9 # [m]
+
+show_animation = True
+
+class State:
+ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0, direction=1):
+ self.x = x
+ self.y = y
+ self.yaw = yaw
+ self.v = v
+ self.direction = direction
+
+ def update(self, a, delta, dt):
+ self.x = self.x + self.v * math.cos(self.yaw) * dt
+ self.y = self.y + self.v * math.sin(self.yaw) * dt
+ self.yaw = self.yaw + self.v / L * math.tan(delta) * dt
+ self.v = self.v + a * dt
+
+class CubicSplinePath:
+ def __init__(self, x, y):
+ x, y = map(np.asarray, (x, y))
+ s = np.append([0],(np.cumsum(np.diff(x)**2) + np.cumsum(np.diff(y)**2))**0.5)
+
+ self.X = interpolate.CubicSpline(s, x)
+ self.Y = interpolate.CubicSpline(s, y)
+
+ self.dX = self.X.derivative(1)
+ self.ddX = self.X.derivative(2)
+
+ self.dY = self.Y.derivative(1)
+ self.ddY = self.Y.derivative(2)
+
+ self.length = s[-1]
+
+ def calc_yaw(self, s):
+ dx, dy = self.dX(s), self.dY(s)
+ return np.arctan2(dy, dx)
+
+ def calc_curvature(self, s):
+ dx, dy = self.dX(s), self.dY(s)
+ ddx, ddy = self.ddX(s), self.ddY(s)
+ return (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2))
+
+ def __find_nearest_point(self, s0, x, y):
+ def calc_distance(_s, *args):
+ _x, _y= self.X(_s), self.Y(_s)
+ return (_x - args[0])**2 + (_y - args[1])**2
+
+ def calc_distance_jacobian(_s, *args):
+ _x, _y = self.X(_s), self.Y(_s)
+ _dx, _dy = self.dX(_s), self.dY(_s)
+ return 2*_dx*(_x - args[0])+2*_dy*(_y-args[1])
+
+ minimum = optimize.fmin_cg(calc_distance, s0, calc_distance_jacobian, args=(x, y), full_output=True, disp=False)
+ return minimum
+
+ def calc_track_error(self, x, y, s0):
+ ret = self.__find_nearest_point(s0, x, y)
+
+ s = ret[0][0]
+ e = ret[1]
+
+ k = self.calc_curvature(s)
+ yaw = self.calc_yaw(s)
+
+ dxl = self.X(s) - x
+ dyl = self.Y(s) - y
+ angle = pi_2_pi(yaw - math.atan2(dyl, dxl))
+ if angle < 0:
+ e*= -1
+
+ return e, k, yaw, s
+
+def pid_control(target, current):
+ a = Kp * (target - current)
+ return a
+
+def pi_2_pi(angle):
+ return angle_mod(angle)
+
+def rear_wheel_feedback_control(state, e, k, yaw_ref):
+ v = state.v
+ th_e = pi_2_pi(state.yaw - yaw_ref)
+
+ omega = v * k * math.cos(th_e) / (1.0 - k * e) - \
+ KTH * abs(v) * th_e - KE * v * math.sin(th_e) * e / th_e
+
+ if th_e == 0.0 or omega == 0.0:
+ return 0.0
+
+ delta = math.atan2(L * omega / v, 1.0)
+
+ return delta
+
+
+def simulate(path_ref, goal):
+ T = 500.0 # max simulation time
+ goal_dis = 0.3
+
+ state = State(x=-0.0, y=-0.0, yaw=0.0, v=0.0)
+
+ time = 0.0
+ x = [state.x]
+ y = [state.y]
+ yaw = [state.yaw]
+ v = [state.v]
+ t = [0.0]
+ goal_flag = False
+
+ s = np.arange(0, path_ref.length, 0.1)
+ e, k, yaw_ref, s0 = path_ref.calc_track_error(state.x, state.y, 0.0)
+
+ while T >= time:
+ e, k, yaw_ref, s0 = path_ref.calc_track_error(state.x, state.y, s0)
+ di = rear_wheel_feedback_control(state, e, k, yaw_ref)
+
+ speed_ref = calc_target_speed(state, yaw_ref)
+ ai = pid_control(speed_ref, state.v)
+ state.update(ai, di, dt)
+
+ time = time + dt
+
+ # check goal
+ dx = state.x - goal[0]
+ dy = state.y - goal[1]
+ if math.hypot(dx, dy) <= goal_dis:
+ print("Goal")
+ goal_flag = True
+ break
+
+ x.append(state.x)
+ y.append(state.y)
+ yaw.append(state.yaw)
+ v.append(state.v)
+ t.append(time)
+
+ if show_animation:
+ plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(path_ref.X(s), path_ref.Y(s), "-r", label="course")
+ plt.plot(x, y, "ob", label="trajectory")
+ plt.plot(path_ref.X(s0), path_ref.Y(s0), "xg", label="target")
+ plt.axis("equal")
+ plt.grid(True)
+ plt.title(f"speed[km/h]:{round(state.v * 3.6, 2):.2f}, target s-param:{s0:.2f}")
+ plt.pause(0.0001)
+
+ return t, x, y, yaw, v, goal_flag
+
+def calc_target_speed(state, yaw_ref):
+ target_speed = 10.0 / 3.6
+
+ dyaw = yaw_ref - state.yaw
+ switch = math.pi / 4.0 <= dyaw < math.pi / 2.0
+
+ if switch:
+ state.direction *= -1
+ return 0.0
+
+ if state.direction != 1:
+ return -target_speed
+
+ return target_speed
+
+def main():
+ print("rear wheel feedback tracking start!!")
+ ax = [0.0, 6.0, 12.5, 5.0, 7.5, 3.0, -1.0]
+ ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0]
+ goal = [ax[-1], ay[-1]]
+
+ reference_path = CubicSplinePath(ax, ay)
+ s = np.arange(0, reference_path.length, 0.1)
+
+ t, x, y, yaw, v, goal_flag = simulate(reference_path, goal)
+
+ # Test
+ assert goal_flag, "Cannot goal"
+
+ if show_animation: # pragma: no cover
+ plt.close()
+ plt.subplots(1)
+ plt.plot(ax, ay, "xb", label="input")
+ plt.plot(reference_path.X(s), reference_path.Y(s), "-r", label="spline")
+ plt.plot(x, y, "-g", label="tracking")
+ plt.grid(True)
+ plt.axis("equal")
+ plt.xlabel("x[m]")
+ plt.ylabel("y[m]")
+ plt.legend()
+
+ plt.subplots(1)
+ plt.plot(s, np.rad2deg(reference_path.calc_yaw(s)), "-r", label="yaw")
+ plt.grid(True)
+ plt.legend()
+ plt.xlabel("line length[m]")
+ plt.ylabel("yaw angle[deg]")
+
+ plt.subplots(1)
+ plt.plot(s, reference_path.calc_curvature(s), "-r", label="curvature")
+ plt.grid(True)
+ plt.legend()
+ plt.xlabel("line length[m]")
+ plt.ylabel("curvature [1/m]")
+
+ plt.show()
+
+if __name__ == '__main__':
+ main()
diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_control/stanley_control.py
similarity index 89%
rename from PathTracking/stanley_controller/stanley_controller.py
rename to PathTracking/stanley_control/stanley_control.py
index addd5ad3a1..01c2ec0229 100644
--- a/PathTracking/stanley_controller/stanley_controller.py
+++ b/PathTracking/stanley_control/stanley_control.py
@@ -4,7 +4,7 @@
author: Atsushi Sakai (@Atsushi_twi)
-Ref:
+Reference:
- [Stanley: The robot that won the DARPA grand challenge](http://isl.ecst.csuchico.edu/DOCS/darpa2005/DARPA%202005%20Stanley.pdf)
- [Autonomous Automobile Path Tracking](https://www.ri.cmu.edu/pub_files/2009/2/Automatic_Steering_Methods_for_Autonomous_Automobile_Path_Tracking.pdf)
@@ -12,16 +12,14 @@
import numpy as np
import matplotlib.pyplot as plt
import sys
-sys.path.append("../../PathPlanning/CubicSpline/")
-
-try:
- import cubic_spline_planner
-except:
- raise
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
+from utils.angle import angle_mod
+from PathPlanning.CubicSpline import cubic_spline_planner
k = 0.5 # control gain
-Kp = 1.0 # speed propotional gain
+Kp = 1.0 # speed proportional gain
dt = 0.1 # [s] time difference
L = 2.9 # [m] Wheel base of vehicle
max_steer = np.radians(30.0) # [rad] max steering angle
@@ -29,7 +27,7 @@
show_animation = True
-class State(object):
+class State:
"""
Class representing the state of a vehicle.
@@ -41,7 +39,7 @@ class State(object):
def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
"""Instantiate the object."""
- super(State, self).__init__()
+ super().__init__()
self.x = x
self.y = y
self.yaw = yaw
@@ -109,13 +107,7 @@ def normalize_angle(angle):
:param angle: (float)
:return: (float) Angle in radian in [-pi, pi]
"""
- while angle > np.pi:
- angle -= 2.0 * np.pi
-
- while angle < -np.pi:
- angle += 2.0 * np.pi
-
- return angle
+ return angle_mod(angle)
def calc_target_index(state, cx, cy):
@@ -127,20 +119,19 @@ def calc_target_index(state, cx, cy):
:param cy: [float]
:return: (int, float)
"""
- # Calc front axle position
+ # Calc front axle position
fx = state.x + L * np.cos(state.yaw)
fy = state.y + L * np.sin(state.yaw)
# Search nearest point index
dx = [fx - icx for icx in cx]
dy = [fy - icy for icy in cy]
- d = [np.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)]
- closest_error = min(d)
- target_idx = d.index(closest_error)
+ d = np.hypot(dx, dy)
+ target_idx = np.argmin(d)
# Project RMS error onto front axle vector
front_axle_vec = [-np.cos(state.yaw + np.pi / 2),
- - np.sin(state.yaw + np.pi / 2)]
+ -np.sin(state.yaw + np.pi / 2)]
error_front_axle = np.dot([dx[target_idx], dy[target_idx]], front_axle_vec)
return target_idx, error_front_axle
@@ -186,6 +177,9 @@ def main():
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect('key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(cx, cy, ".r", label="course")
plt.plot(x, y, "-b", label="trajectory")
plt.plot(cx[target_idx], cy[target_idx], "xg", label="target")
diff --git a/README.md b/README.md
index 0aa7220d40..d1b801f219 100644
--- a/README.md
+++ b/README.md
@@ -1,18 +1,12 @@
-
+
# PythonRobotics
-[](https://travis-ci.org/AtsushiSakai/PythonRobotics)
-[](https://pythonrobotics.readthedocs.io/en/latest/?badge=latest)
+
+
+
[](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics)
-[](https://coveralls.io/github/AtsushiSakai/PythonRobotics?branch=master)
-[](https://lgtm.com/projects/g/AtsushiSakai/PythonRobotics/context:python)
-[](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/overview/master)
-[](https://github.com/AtsushiSakai/PythonRobotics)
-[](https://saythanks.io/to/AtsushiSakai)
-
-Python codes for robotics algorithm.
-
+Python codes and [textbook](https://atsushisakai.github.io/PythonRobotics/index.html) for robotics algorithm.
# Table of Contents
@@ -27,26 +21,28 @@ Python codes for robotics algorithm.
* [Mapping](#mapping)
* [Gaussian grid map](#gaussian-grid-map)
* [Ray casting grid map](#ray-casting-grid-map)
- * [Lidar to grid map](#lidar-to-grid-map)
+ * [Lidar to grid map](#lidar-to-grid-map)
* [k-means object clustering](#k-means-object-clustering)
* [Rectangle fitting](#rectangle-fitting)
* [SLAM](#slam)
* [Iterative Closest Point (ICP) Matching](#iterative-closest-point-icp-matching)
* [FastSLAM 1.0](#fastslam-10)
- * [Pose Optimization SLAM](#pose-optimization-slam)
* [Path Planning](#path-planning)
* [Dynamic Window Approach](#dynamic-window-approach)
* [Grid based search](#grid-based-search)
* [Dijkstra algorithm](#dijkstra-algorithm)
* [A* algorithm](#a-algorithm)
+ * [D* algorithm](#d-algorithm)
+ * [D* Lite algorithm](#d-lite-algorithm)
* [Potential Field algorithm](#potential-field-algorithm)
+ * [Grid based coverage path planning](#grid-based-coverage-path-planning)
* [State Lattice Planning](#state-lattice-planning)
* [Biased polar sampling](#biased-polar-sampling)
* [Lane sampling](#lane-sampling)
* [Probabilistic Road-Map (PRM) planning](#probabilistic-road-map-prm-planning)
* [Rapidly-Exploring Random Trees (RRT)](#rapidly-exploring-random-trees-rrt)
* [RRT*](#rrt)
- * [RRT* with reeds-sheep path](#rrt-with-reeds-sheep-path)
+ * [RRT* with reeds-shepp path](#rrt-with-reeds-shepp-path)
* [LQR-RRT*](#lqr-rrt)
* [Quintic polynomials planning](#quintic-polynomials-planning)
* [Reeds Shepp planning](#reeds-shepp-planning)
@@ -70,12 +66,16 @@ Python codes for robotics algorithm.
* [License](#license)
* [Use-case](#use-case)
* [Contribution](#contribution)
+ * [Citing](#citing)
* [Support](#support)
+ * [Sponsors](#sponsors)
+ * [JetBrains](#JetBrains)
+ * [1Password](#1password)
* [Authors](#authors)
-# What is this?
+# What is PythonRobotics?
-This is a Python code collection of robotics algorithms, especially for autonomous navigation.
+PythonRobotics is a Python code collection and a [textbook](https://atsushisakai.github.io/PythonRobotics/index.html) of robotics algorithms.
Features:
@@ -85,32 +85,52 @@ Features:
3. Minimum dependency.
-See this paper for more details:
+See this documentation
-- [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib))
+- [Getting Started — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/0_getting_started/1_what_is_python_robotics.html)
+or this Youtube video:
-# Requirements
+- [PythonRobotics project audio overview](https://www.youtube.com/watch?v=uMeRnNoJAfU)
-- Python 3.6.x (2.7 is not supported)
+or this paper for more details:
+
+- [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib))
-- numpy
-- scipy
+# Requirements to run the code
-- matplotlib
+For running each sample code:
-- pandas
+- [Python 3.13.x](https://www.python.org/)
+
+- [NumPy](https://numpy.org/)
+
+- [SciPy](https://scipy.org/)
+
+- [Matplotlib](https://matplotlib.org/)
+
+- [cvxpy](https://www.cvxpy.org/)
-- [cvxpy](http://www.cvxpy.org/en/latest/)
+For development:
+
+- [pytest](https://pytest.org/) (for unit tests)
+
+- [pytest-xdist](https://pypi.org/project/pytest-xdist/) (for parallel unit tests)
+
+- [mypy](https://mypy-lang.org/) (for type check)
+
+- [sphinx](https://www.sphinx-doc.org/) (for document generation)
+
+- [pycodestyle](https://pypi.org/project/pycodestyle/) (for code style check)
-# Documentation
+# Documentation (Textbook)
This README only shows some examples of this project.
If you are interested in other examples or mathematical backgrounds of each algorithm,
-You can check the full documentation online: [https://pythonrobotics.readthedocs.io/](https://pythonrobotics.readthedocs.io/)
+You can check the full documentation (textbook) online: [Welcome to PythonRobotics’s documentation\! — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/index.html)
All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation gifs of PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs)
@@ -118,14 +138,24 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation
1. Clone this repo.
-> git clone https://github.com/AtsushiSakai/PythonRobotics.git
+ ```terminal
+ git clone https://github.com/AtsushiSakai/PythonRobotics.git
+ ```
+
-> cd PythonRobotics/
+2. Install the required libraries.
+- using conda :
-2. Install the required libraries. You can use environment.yml with conda command.
+ ```terminal
+ conda env create -f requirements/environment.yml
+ ```
+
+- using pip :
-> conda env create -f environment.yml
+ ```terminal
+ pip install -r requirements/requirements.txt
+ ```
3. Execute python script in each directory.
@@ -136,9 +166,11 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation
## Extended Kalman Filter localization
-
+
-Documentation: [Notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb)
+Reference
+
+- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.html)
## Particle filter localization
@@ -148,13 +180,13 @@ This is a sensor fusion localization with Particle Filter(PF).
The blue line is true trajectory, the black line is dead reckoning trajectory,
-and the red line is estimated trajectory with PF.
+and the red line is an estimated trajectory with PF.
It is assumed that the robot can measure a distance from landmarks (RFID).
-This measurements are used for PF localization.
+These measurements are used for PF localization.
-Ref:
+Reference
- [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/)
@@ -175,7 +207,7 @@ The filter integrates speed input and range observations from RFID for localizat
Initial position is not needed.
-Ref:
+Reference
- [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/)
@@ -197,7 +229,7 @@ This is a 2D ray casting grid mapping example.
This example shows how to convert a 2D range measurement to a grid map.
-
+
## k-means object clustering
@@ -220,11 +252,11 @@ Simultaneous Localization and Mapping(SLAM) examples
This is a 2D ICP matching example with singular value decomposition.
-It can calculate a rotation matrix and a translation vector between points to points.
+It can calculate a rotation matrix, and a translation vector between points and points.

-Ref:
+Reference
- [Introduction to Mobile Robotics: Iterative Closest Point Algorithm](https://cs.gmu.edu/~kosecka/cs685/cs685-icp.pdf)
@@ -243,19 +275,13 @@ Black points are landmarks, blue crosses are estimated landmark positions by Fas

-Ref:
+Reference
- [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/)
- [SLAM simulations by Tim Bailey](http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm)
-## Pose Optimization SLAM
-
-This is a graph based pose optimization SLAM example.
-
-
-
# Path Planning
## Dynamic Window Approach
@@ -271,7 +297,7 @@ This is a 2D navigation sample code with Dynamic Window Approach.
### Dijkstra algorithm
-This is a 2D grid based shortest path planning with Dijkstra's algorithm.
+This is a 2D grid based the shortest path planning with Dijkstra's algorithm.

@@ -279,7 +305,7 @@ In the animation, cyan points are searched nodes.
### A\* algorithm
-This is a 2D grid based shortest path planning with A star algorithm.
+This is a 2D grid based the shortest path planning with A star algorithm.

@@ -287,6 +313,31 @@ In the animation, cyan points are searched nodes.
Its heuristic is 2D Euclid distance.
+### D\* algorithm
+
+This is a 2D grid based the shortest path planning with D star algorithm.
+
+
+
+The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm.
+
+Reference
+
+- [D* Algorithm Wikipedia](https://en.wikipedia.org/wiki/D*)
+
+### D\* Lite algorithm
+
+This algorithm finds the shortest path between two points while rerouting when obstacles are discovered. It has been implemented here for a 2D grid.
+
+
+
+The animation shows a robot finding its path and rerouting to avoid obstacles as they are discovered using the D* Lite search algorithm.
+
+Refs:
+
+- [D* Lite](http://idm-lab.org/bib/abstracts/papers/aaai02b.pdf)
+- [Improved Fast Replanning for Robot Navigation in Unknown Terrain](http://www.cs.cmu.edu/~maxim/files/dlite_icra02.pdf)
+
### Potential Field algorithm
This is a 2D grid based path planning with Potential Field algorithm.
@@ -295,21 +346,27 @@ This is a 2D grid based path planning with Potential Field algorithm.
In the animation, the blue heat map shows potential value on each grid.
-Ref:
+Reference
- [Robotic Motion Planning:Potential Functions](https://www.cs.cmu.edu/~motionplanning/lecture/Chap4-Potential-Field_howie.pdf)
+### Grid based coverage path planning
+
+This is a 2D grid based coverage path planning simulation.
+
+
+
## State Lattice Planning
This script is a path planning code with state lattice planning.
This code uses the model predictive trajectory generator to solve boundary problem.
-Ref:
+Reference
-- [Optimal rough terrain trajectory generation for wheeled mobile robots](http://journals.sagepub.com/doi/pdf/10.1177/0278364906075328)
+- [Optimal rough terrain trajectory generation for wheeled mobile robots](https://journals.sagepub.com/doi/pdf/10.1177/0278364906075328)
-- [State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments](http://www.frc.ri.cmu.edu/~alonzo/pubs/papers/JFR_08_SS_Sampling.pdf)
+- [State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments](https://www.cs.cmu.edu/~alonzo/pubs/papers/JFR_08_SS_Sampling.pdf)
### Biased polar sampling
@@ -333,7 +390,7 @@ Cyan crosses means searched points with Dijkstra method,
The red line is the final path of PRM.
-Ref:
+Reference
- [Probabilistic roadmap \- Wikipedia](https://en.wikipedia.org/wiki/Probabilistic_roadmap)
@@ -349,17 +406,17 @@ This is a path planning code with RRT\*
Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions.
-Ref:
+Reference
- [Incremental Sampling-based Algorithms for Optimal Motion Planning](https://arxiv.org/abs/1005.0416)
-- [Sampling-based Algorithms for Optimal Motion Planning](http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.419.5503&rep=rep1&type=pdf)
+- [Sampling-based Algorithms for Optimal Motion Planning](https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf&doi=bddbc99f97173430aa49a0ada53ab5bade5902fa)
-### RRT\* with reeds-sheep path
+### RRT\* with reeds-shepp path
-)
+
-Path planning for a car robot with RRT\* and reeds sheep path planner.
+Path planning for a car robot with RRT\* and reeds shepp path planner.
### LQR-RRT\*
@@ -367,11 +424,11 @@ This is a path planning simulation with LQR-RRT\*.
A double integrator motion model is used for LQR local planner.
-
+
-Ref:
+Reference
-- [LQR\-RRT\*: Optimal Sampling\-Based Motion Planning with Automatically Derived Extension Heuristics](http://lis.csail.mit.edu/pubs/perez-icra12.pdf)
+- [LQR\-RRT\*: Optimal Sampling\-Based Motion Planning with Automatically Derived Extension Heuristics](https://lis.csail.mit.edu/pubs/perez-icra12.pdf)
- [MahanFathi/LQR\-RRTstar: LQR\-RRT\* method is used for random motion planning of a simple pendulum in its phase plot](https://github.com/MahanFathi/LQR-RRTstar)
@@ -382,11 +439,11 @@ Motion planning with quintic polynomials.

-It can calculate 2D path, velocity, and acceleration profile based on quintic polynomials.
+It can calculate a 2D path, velocity, and acceleration profile based on quintic polynomials.
-Ref:
+Reference
-- [Local Path Planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/)
+- [Local Path Planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/)
## Reeds Shepp planning
@@ -394,7 +451,7 @@ A sample code with Reeds Shepp path planning.

-Ref:
+Reference
- [15.3.2 Reeds\-Shepp Curves](http://planning.cs.uiuc.edu/node822.html)
@@ -418,9 +475,9 @@ This is optimal trajectory generation in a Frenet Frame.
The cyan line is the target course and black crosses are obstacles.
-The red line is predicted path.
+The red line is the predicted path.
-Ref:
+Reference
- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame](https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf)
@@ -433,9 +490,9 @@ Ref:
This is a simulation of moving to a pose control
-
+
-Ref:
+Reference
- [P. I. Corke, "Robotics, Vision and Control" \| SpringerLink p102](https://link.springer.com/book/10.1007/978-3-642-20144-8)
@@ -446,7 +503,7 @@ Path tracking simulation with Stanley steering control and PID speed control.

-Ref:
+Reference
- [Stanley: The robot that won the DARPA grand challenge](http://robots.stanford.edu/papers/thrun.stanley05.pdf)
@@ -460,7 +517,7 @@ Path tracking simulation with rear wheel feedback steering control and PID speed

-Ref:
+Reference
- [A Survey of Motion Planning and Control Techniques for Self-driving Urban Vehicles](https://arxiv.org/abs/1604.07446)
@@ -471,20 +528,22 @@ Path tracking simulation with LQR speed and steering control.

-Ref:
+Reference
-- [Towards fully autonomous driving: Systems and algorithms \- IEEE Conference Publication](http://ieeexplore.ieee.org/document/5940562/)
+- [Towards fully autonomous driving: Systems and algorithms \- IEEE Conference Publication](https://ieeexplore.ieee.org/document/5940562/)
## Model predictive speed and steering control
Path tracking simulation with iterative linear model predictive speed and steering control.
-
+
-Ref:
+Reference
-- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb)
+- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.html)
+
+- [Real\-time Model Predictive Control \(MPC\), ACADO, Python \| Work\-is\-Playing](http://grauonline.de/wordpress/?page_id=3244)
## Nonlinear Model predictive control with C-GMRES
@@ -492,9 +551,9 @@ A motion planning and path tracking simulation with NMPC of C-GMRES

-Ref:
+Reference
-- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb)
+- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc.html)
# Arm Navigation
@@ -503,9 +562,9 @@ Ref:
N joint arm to a point control simulation.
-This is a interactive simulation.
+This is an interactive simulation.
-You can set the goal position of the end effector with left-click on the ploting area.
+You can set the goal position of the end effector with left-click on the plotting area.

@@ -532,17 +591,17 @@ This is a 3d trajectory generation simulation for a rocket powered landing.

-Ref:
+Reference
-- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb)
+- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing.html)
# Bipedal
## bipedal planner with inverted pendulum
-This is a bipedal planner for modifying footsteps with inverted pendulum.
+This is a bipedal planner for modifying footsteps for an inverted pendulum.
-You can set the footsteps and the planner will modify those automatically.
+You can set the footsteps, and the planner will modify those automatically.

@@ -552,60 +611,48 @@ MIT
# Use-case
-If this project helps your robotics project, please let me know with [](https://saythanks.io/to/AtsushiSakai).
+If this project helps your robotics project, please let me know with creating an issue.
Your robot's video, which is using PythonRobotics, is very welcome!!
-This is a list of other user's comment and references:[users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md)
+This is a list of user's comment and references:[users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md)
# Contribution
-A small PR like bug fix is welcome.
-
-If your PR is merged multiple times, I will add your account to the author list.
-
-# Support
-
-If you or your company would like to support this project, please consider:
-
-- [Become a backer or sponsor on Patreon](https://www.patreon.com/myenigma)
-
-- [One-time donation via PayPal](https://www.paypal.me/myenigmapay/)
+Any contribution is welcome!!
-You can add your name or your company logo in README if you are a patron.
+Please check this document:[How To Contribute — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/0_getting_started/3_how_to_contribute.html)
-E-mail consultant is also available.
+# Citing
-
+If you use this project's code for your academic work, we encourage you to cite [our papers](https://arxiv.org/abs/1808.10703)
-Your comment using [](https://saythanks.io/to/AtsushiSakai) is also welcome.
+If you use this project's code in industry, we'd love to hear from you as well; feel free to reach out to the developers directly.
-This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md)
-
-# Authors
-
-- [Atsushi Sakai](https://github.com/AtsushiSakai/) ([@Atsushi_twi](https://twitter.com/Atsushi_twi))
-
-- [Daniel Ingram](https://github.com/daniel-s-ingram)
-
-- [Joe Dinius](https://github.com/jwdinius)
-
-- [Karan Chawla](https://github.com/karanchawla)
-
-- [Antonin RAFFIN](https://github.com/araffin)
-
-- [Alexis Paques](https://github.com/AlexisTM)
+# Supporting this project
+If you or your company would like to support this project, please consider:
+- [Sponsor @AtsushiSakai on GitHub Sponsors](https://github.com/sponsors/AtsushiSakai)
+- [Become a backer or sponsor on Patreon](https://www.patreon.com/myenigma)
+- [One-time donation via PayPal](https://www.paypal.com/paypalme/myenigmapay/)
+If you would like to support us in some other way, please contact with creating an issue.
+## Sponsors
+### [JetBrains](https://www.jetbrains.com/)
+They are providing a free license of their IDEs for this OSS development.
+### [1Password](https://github.com/1Password/for-open-source)
+They are providing a free license of their 1Password team license for this OSS project.
+# Authors
+- [Contributors to AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics/graphs/contributors)
diff --git a/SECURITY.md b/SECURITY.md
new file mode 100644
index 0000000000..53dcafa450
--- /dev/null
+++ b/SECURITY.md
@@ -0,0 +1,13 @@
+# Security Policy
+
+## Supported Versions
+
+In this project, we are only support latest code.
+
+| Version | Supported |
+| ------- | ------------------ |
+| latest | :white_check_mark: |
+
+## Reporting a Vulnerability
+
+If you find any security related problem, let us know by creating an issue about it.
diff --git a/SLAM/EKFSLAM/ekf_slam.ipynb b/SLAM/EKFSLAM/ekf_slam.ipynb
deleted file mode 100644
index 6509373d2b..0000000000
--- a/SLAM/EKFSLAM/ekf_slam.ipynb
+++ /dev/null
@@ -1,1581 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "# EKF SLAM"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 11,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 11,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"animation.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Simulation\n",
- "\n",
- "This is a simulation of EKF SLAM. \n",
- "\n",
- "- Black stars: landmarks\n",
- "- Green crosses: estimates of landmark positions\n",
- "- Black line: dead reckoning \n",
- "- Blue line: ground truth\n",
- "- Red line: EKF SLAM position estimation"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Introduction\n",
- "\n",
- "EKF SLAM models the SLAM problem in a single EKF where the modeled state is both the pose $(x, y, \\theta)$ and \n",
- "an array of landmarks $[(x_1, y_1), (x_2, x_y), ... , (x_n, y_n)]$ for $n$ landmarks. The covariance between each of the positions and landmarks are also tracked. "
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\\begin{equation}\n",
- "X = \\begin{bmatrix} x \\\\ y \\\\ \\theta \\\\ x_1 \\\\ y_1 \\\\ x_2 \\\\ y_2 \\\\ \\dots \\\\ x_n \\\\ y_n \\end{bmatrix}\n",
- "\\end{equation}\n",
- "\n",
- "\\begin{equation}\n",
- "P = \\begin{bmatrix} \n",
- "\\sigma_{xx} & \\sigma_{xy} & \\sigma_{x\\theta} & \\sigma_{xx_1} & \\sigma_{xy_1} & \\sigma_{xx_2} & \\sigma_{xy_2} & \\dots & \\sigma_{xx_n} & \\sigma_{xy_n} \\\\\n",
- "\\sigma_{yx} & \\sigma_{yy} & \\sigma_{y\\theta} & \\sigma_{yx_1} & \\sigma_{yy_1} & \\sigma_{yx_2} & \\sigma_{yy_2} & \\dots & \\sigma_{yx_n} & \\sigma_{yy_n} \\\\\n",
- " & & & & \\vdots & & & & & \\\\\n",
- "\\sigma_{x_nx} & \\sigma_{x_ny} & \\sigma_{x_n\\theta} & \\sigma_{x_nx_1} & \\sigma_{x_ny_1} & \\sigma_{x_nx_2} & \\sigma_{x_ny_2} & \\dots & \\sigma_{x_nx_n} & \\sigma_{x_ny_n}\n",
- "\\end{bmatrix}\n",
- "\\end{equation}"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "A single estimate of the pose is tracked over time, while the confidence in the pose is tracked by the \n",
- "covariance matrix $P$. $P$ is a symmetric square matrix whith each element in the matrix corresponding to the \n",
- "covariance between two parts of the system. For example, $\\sigma_{xy}$ represents the covariance between the \n",
- "belief of $x$ and $y$ and is equal to $\\sigma_{yx}$. \n",
- "\n",
- "The state can be represented more concisely as follows. "
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\\begin{equation}\n",
- "X = \\begin{bmatrix} x \\\\ m \\end{bmatrix}\n",
- "\\end{equation}\n",
- "\\begin{equation}\n",
- "P = \\begin{bmatrix} \n",
- "\\Sigma_{xx} & \\Sigma_{xm}\\\\\n",
- "\\Sigma_{mx} & \\Sigma_{mm}\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation}"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Here the state simplifies to a combination of pose ($x$) and map ($m$). The covariance matrix becomes easier to \n",
- "understand and simply reads as the uncertainty of the robots pose ($\\Sigma_{xx}$), the uncertainty of the \n",
- "map ($\\Sigma_{mm}$), and the uncertainty of the robots pose with respect to the map and vice versa \n",
- "($\\Sigma_{xm}$, $\\Sigma_{mx}$).\n",
- "\n",
- "Take care to note the difference between $X$ (state) and $x$ (pose). "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 22,
- "metadata": {},
- "outputs": [],
- "source": [
- "\"\"\"\n",
- "Extended Kalman Filter SLAM example\n",
- "original author: Atsushi Sakai (@Atsushi_twi)\n",
- "notebook author: Andrew Tu (drewtu2)\n",
- "\"\"\"\n",
- "\n",
- "import math\n",
- "import numpy as np\n",
- "%matplotlib notebook\n",
- "import matplotlib.pyplot as plt\n",
- "\n",
- "\n",
- "# EKF state covariance\n",
- "Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2 # Change in covariance\n",
- "\n",
- "# Simulation parameter\n",
- "Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 # Sensor Noise\n",
- "Rsim = np.diag([1.0, np.deg2rad(10.0)])**2 # Process Noise\n",
- "\n",
- "DT = 0.1 # time tick [s]\n",
- "SIM_TIME = 50.0 # simulation time [s]\n",
- "MAX_RANGE = 20.0 # maximum observation range\n",
- "M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.\n",
- "STATE_SIZE = 3 # State size [x,y,yaw]\n",
- "LM_SIZE = 2 # LM state size [x,y]\n",
- "\n",
- "show_animation = True"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Algorithm Walkthrough\n",
- "\n",
- "At each time step, the following is done. \n",
- "- predict the new state using the control functions\n",
- "- update the belief in landmark positions based on the estimated state and measurements"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [],
- "source": [
- "def ekf_slam(xEst, PEst, u, z):\n",
- " \"\"\"\n",
- " Performs an iteration of EKF SLAM from the available information. \n",
- " \n",
- " :param xEst: the belief in last position\n",
- " :param PEst: the uncertainty in last position\n",
- " :param u: the control function applied to the last position \n",
- " :param z: measurements at this step\n",
- " :returns: the next estimated position and associated covariance\n",
- " \"\"\"\n",
- " S = STATE_SIZE\n",
- "\n",
- " # Predict\n",
- " xEst, PEst, G, Fx = predict(xEst, PEst, u)\n",
- " initP = np.eye(2)\n",
- "\n",
- " # Update\n",
- " xEst, PEst = update(xEst, PEst, u, z, initP)\n",
- "\n",
- " return xEst, PEst\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## 1- Predict\n",
- "**Predict State update:** The following equations describe the predicted motion model of the robot in case we provide only the control $(v,w)$, which are the linear and angular velocity repsectively. \n",
- "\n",
- "$\\begin{equation*}\n",
- "F=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 \\\\\n",
- "0 & 1 & 0 \\\\\n",
- "0 & 0 & 1 \n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "B=\n",
- "\\begin{bmatrix}\n",
- "\\Delta t cos(\\theta) & 0\\\\\n",
- "\\Delta t sin(\\theta) & 0\\\\\n",
- "0 & \\Delta t\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "U=\n",
- "\\begin{bmatrix}\n",
- "v_t\\\\\n",
- "w_t\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "X = FX + BU \n",
- "\\end{equation*}$\n",
- "\n",
- "\n",
- "$\\begin{equation*}\n",
- "\\begin{bmatrix}\n",
- "x_{t+1} \\\\\n",
- "y_{t+1} \\\\\n",
- "\\theta_{t+1}\n",
- "\\end{bmatrix}=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 \\\\\n",
- "0 & 1 & 0 \\\\\n",
- "0 & 0 & 1 \n",
- "\\end{bmatrix}\\begin{bmatrix}\n",
- "x_{t} \\\\\n",
- "y_{t} \\\\\n",
- "\\theta_{t}\n",
- "\\end{bmatrix}+\n",
- "\\begin{bmatrix}\n",
- "\\Delta t cos(\\theta) & 0\\\\\n",
- "\\Delta t sin(\\theta) & 0\\\\\n",
- "0 & \\Delta t\n",
- "\\end{bmatrix}\n",
- "\\begin{bmatrix}\n",
- "v_{t} + \\sigma_v\\\\\n",
- "w_{t} + \\sigma_w\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "Notice that while $U$ is only defined by $v_t$ and $w_t$, in the actual calcuations, a $+\\sigma_v$ and \n",
- "$+\\sigma_w$ appear. These values represent the error bewteen the given control inputs and the actual control \n",
- "inputs. \n",
- "\n",
- "As a result, the simulation is set up as the following. $R$ represents the process noise which is added to the \n",
- "control inputs to simulate noise experienced in the real world. A set of truth values are computed from the raw \n",
- "control values while the values dead reckoning values incorporate the error into the estimation. \n",
- "\n",
- "$\\begin{equation*}\n",
- "R=\n",
- "\\begin{bmatrix}\n",
- "\\sigma_v\\\\\n",
- "\\sigma_w\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "X_{true} = FX + B(U)\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "X_{DR} = FX + B(U + R)\n",
- "\\end{equation*}$\n",
- "\n",
- "The implementation of the motion model prediciton code is shown in `motion_model`. The `observation` function \n",
- "shows how the simulation uses (or doesn't use) the process noise `Rsim` to the find the ground truth and dead reckoning estimtates of the pose.\n",
- "\n",
- "**Predict covariance:** Add the state covariance to the the current uncertainty of the EKF. At each time step, the uncertainty in the system grows by the covariance of the pose, $Cx$. \n",
- "\n",
- "$\n",
- "P = G^TPG + Cx\n",
- "$\n",
- "\n",
- "Notice this uncertainty is only growing with respect to the pose, not the landmarks. "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [],
- "source": [
- "def predict(xEst, PEst, u):\n",
- " \"\"\"\n",
- " Performs the prediction step of EKF SLAM\n",
- " \n",
- " :param xEst: nx1 state vector\n",
- " :param PEst: nxn covariacne matrix\n",
- " :param u: 2x1 control vector\n",
- " :returns: predicted state vector, predicted covariance, jacobian of control vector, transition fx\n",
- " \"\"\"\n",
- " S = STATE_SIZE\n",
- " xEst[0:S] = motion_model(xEst[0:S], u)\n",
- " G, Fx = jacob_motion(xEst[0:S], u)\n",
- " # Fx is an an identity matrix of size (STATE_SIZE)\n",
- " # sigma = G*sigma*G.T + Noise\n",
- " PEst[0:S, 0:S] = G.T * PEst[0:S, 0:S] * G + Fx.T * Cx * Fx\n",
- " return xEst, PEst, G, Fx"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [],
- "source": [
- "def motion_model(x, u):\n",
- " \"\"\"\n",
- " Computes the motion model based on current state and input function. \n",
- " \n",
- " :param x: 3x1 pose estimation\n",
- " :param u: 2x1 control input [v; w]\n",
- " :returns: the resutling state after the control function is applied\n",
- " \"\"\"\n",
- " F = np.array([[1.0, 0, 0],\n",
- " [0, 1.0, 0],\n",
- " [0, 0, 1.0]])\n",
- "\n",
- " B = np.array([[DT * math.cos(x[2, 0]), 0],\n",
- " [DT * math.sin(x[2, 0]), 0],\n",
- " [0.0, DT]])\n",
- "\n",
- " x = (F @ x) + (B @ u)\n",
- " return x"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## 2 - Update\n",
- "In the update phase, the observations of nearby landmarks are used to correct the location estimate. \n",
- "\n",
- "For every landmark observed, it is associated to a particular landmark in the known map. If no landmark exists \n",
- "in the position surrounding the landmark, it is taken as a NEW landmark. The distance threshold for how far a \n",
- "landmark must be from the next known landmark before its considered to be a new landmark is set by `M_DIST_TH`.\n",
- "\n",
- "With an observation associated to the appropriate landmark, the **innovation** can be calculated. Innovation \n",
- "($y$) is the difference between the observation and the observation that *should* have been made if the \n",
- "observation were made from the pose predicted in the predict stage.\n",
- "\n",
- "$\n",
- "y = z_t - h(X)\n",
- "$\n",
- "\n",
- "With the innovation calculated, the question becomes which to trust more - the observations or the predictions? \n",
- "To determine this, we calculate the Kalman Gain - a percent of how much of the innovation to add to the \n",
- "prediction based on the uncertainty in the predict step and the update step. \n",
- "\n",
- "$\n",
- "K = \\bar{P_t}H_t^T(H_t\\bar{P_t}H_t^T + Q_t)^{-1}\n",
- "$\n",
- "In these equations, $H$ is the jacobian of the measurement function. The multiplications by $H^T$ and $H$ \n",
- "represent the application of the delta to the measurement covariance. \n",
- "Intuitively, this equation is applying the following from the single variate Kalman equation but in the \n",
- "multivariate form, i.e. finding the ratio of the uncertianty of the process compared the measurment. \n",
- "\n",
- "$\n",
- "K = \\frac{\\bar{P_t}}{\\bar{P_t} + Q_t}\n",
- "$\n",
- "\n",
- "If $Q_t << \\bar{P_t}$, (i.e. the measurement covariance is low relative to the current estimate), then the \n",
- "Kalman gain will be $~1$. This results in adding all of the innovation to the estimate -- and therefore \n",
- "completely believing the measurement. \n",
- "\n",
- "However, if $Q_t >> \\bar{P_t}$ then the Kalman gain will go to 0, signaling a high trust in the process \n",
- "and little trust in the measurement.\n",
- "\n",
- "The update is captured in the following. \n",
- "\n",
- "$\n",
- "xUpdate = xEst + (K * y)\n",
- "$\n",
- "\n",
- "Of course, the covariance must also be updated as well to account for the changing uncertainty. \n",
- "\n",
- "$\n",
- "P_{t} = (I-K_tH_t)\\bar{P_t}\n",
- "$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 23,
- "metadata": {},
- "outputs": [],
- "source": [
- "def update(xEst, PEst, u, z, initP):\n",
- " \"\"\"\n",
- " Performs the update step of EKF SLAM\n",
- " \n",
- " :param xEst: nx1 the predicted pose of the system and the pose of the landmarks\n",
- " :param PEst: nxn the predicted covariance\n",
- " :param u: 2x1 the control function \n",
- " :param z: the measurements read at new position\n",
- " :param initP: 2x2 an identity matrix acting as the initial covariance\n",
- " :returns: the updated state and covariance for the system\n",
- " \"\"\"\n",
- " for iz in range(len(z[:, 0])): # for each observation\n",
- " minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) # associate to a known landmark\n",
- "\n",
- " nLM = calc_n_LM(xEst) # number of landmarks we currently know about\n",
- " \n",
- " if minid == nLM: # Landmark is a NEW landmark\n",
- " print(\"New LM\")\n",
- " # Extend state and covariance matrix\n",
- " xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :])))\n",
- " PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),\n",
- " np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))\n",
- " xEst = xAug\n",
- " PEst = PAug\n",
- " \n",
- " lm = get_LM_Pos_from_state(xEst, minid)\n",
- " y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid)\n",
- "\n",
- " K = (PEst @ H.T) @ np.linalg.inv(S) # Calculate Kalman Gain\n",
- " xEst = xEst + (K @ y)\n",
- " PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst\n",
- " \n",
- " xEst[2] = pi_2_pi(xEst[2])\n",
- " return xEst, PEst\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 19,
- "metadata": {},
- "outputs": [],
- "source": [
- "def calc_innovation(lm, xEst, PEst, z, LMid):\n",
- " \"\"\"\n",
- " Calculates the innovation based on expected position and landmark position\n",
- " \n",
- " :param lm: landmark position\n",
- " :param xEst: estimated position/state\n",
- " :param PEst: estimated covariance\n",
- " :param z: read measurements\n",
- " :param LMid: landmark id\n",
- " :returns: returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain\n",
- " \"\"\"\n",
- " delta = lm - xEst[0:2]\n",
- " q = (delta.T @ delta)[0, 0]\n",
- " zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]\n",
- " zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]])\n",
- " # zp is the expected measurement based on xEst and the expected landmark position\n",
- " \n",
- " y = (z - zp).T # y = innovation\n",
- " y[1] = pi_2_pi(y[1])\n",
- " \n",
- " H = jacobH(q, delta, xEst, LMid + 1)\n",
- " S = H @ PEst @ H.T + Cx[0:2, 0:2]\n",
- "\n",
- " return y, S, H\n",
- "\n",
- "def jacobH(q, delta, x, i):\n",
- " \"\"\"\n",
- " Calculates the jacobian of the measurement function\n",
- " \n",
- " :param q: the range from the system pose to the landmark\n",
- " :param delta: the difference between a landmark position and the estimated system position\n",
- " :param x: the state, including the estimated system position\n",
- " :param i: landmark id + 1\n",
- " :returns: the jacobian H\n",
- " \"\"\"\n",
- " sq = math.sqrt(q)\n",
- " G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],\n",
- " [delta[1, 0], - delta[0, 0], - 1.0, - delta[1, 0], delta[0, 0]]])\n",
- "\n",
- " G = G / q\n",
- " nLM = calc_n_LM(x)\n",
- " F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))\n",
- " F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),\n",
- " np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))\n",
- "\n",
- " F = np.vstack((F1, F2))\n",
- "\n",
- " H = G @ F\n",
- "\n",
- " return H"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Observation Step\n",
- "The observation step described here is outside the main EKF SLAM process and is primarily used as a method of\n",
- "driving the simulation. The observations funciton is in charge of calcualting how the poses of the robots change \n",
- "and accumulate error over time, and the theoretical measuremnts that are expected as a result of each \n",
- "measurement. \n",
- "\n",
- "Observations are based on the TRUE position of the robot. Error in dead reckoning and control functions are \n",
- "passed along here as well. "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 24,
- "metadata": {},
- "outputs": [],
- "source": [
- "def observation(xTrue, xd, u, RFID):\n",
- " \"\"\"\n",
- " :param xTrue: the true pose of the system\n",
- " :param xd: the current noisy estimate of the system\n",
- " :param u: the current control input\n",
- " :param RFID: the true position of the landmarks\n",
- " \n",
- " :returns: Computes the true position, observations, dead reckoning (noisy) position, \n",
- " and noisy control function\n",
- " \"\"\"\n",
- " xTrue = motion_model(xTrue, u)\n",
- "\n",
- " # add noise to gps x-y\n",
- " z = np.zeros((0, 3))\n",
- "\n",
- " for i in range(len(RFID[:, 0])): # Test all beacons, only add the ones we can see (within MAX_RANGE)\n",
- "\n",
- " dx = RFID[i, 0] - xTrue[0, 0]\n",
- " dy = RFID[i, 1] - xTrue[1, 0]\n",
- " d = math.sqrt(dx**2 + dy**2)\n",
- " angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])\n",
- " if d <= MAX_RANGE:\n",
- " dn = d + np.random.randn() * Qsim[0, 0] # add noise\n",
- " anglen = angle + np.random.randn() * Qsim[1, 1] # add noise\n",
- " zi = np.array([dn, anglen, i])\n",
- " z = np.vstack((z, zi))\n",
- "\n",
- " # add noise to input\n",
- " ud = np.array([[\n",
- " u[0, 0] + np.random.randn() * Rsim[0, 0],\n",
- " u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T\n",
- "\n",
- " xd = motion_model(xd, ud)\n",
- " return xTrue, z, xd, ud"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 21,
- "metadata": {},
- "outputs": [],
- "source": [
- "def calc_n_LM(x):\n",
- " \"\"\"\n",
- " Calculates the number of landmarks currently tracked in the state\n",
- " :param x: the state\n",
- " :returns: the number of landmarks n\n",
- " \"\"\"\n",
- " n = int((len(x) - STATE_SIZE) / LM_SIZE)\n",
- " return n\n",
- "\n",
- "\n",
- "def jacob_motion(x, u):\n",
- " \"\"\"\n",
- " Calculates the jacobian of motion model. \n",
- " \n",
- " :param x: The state, including the estimated position of the system\n",
- " :param u: The control function\n",
- " :returns: G: Jacobian\n",
- " Fx: STATE_SIZE x (STATE_SIZE + 2 * num_landmarks) matrix where the left side is an identity matrix\n",
- " \"\"\"\n",
- " \n",
- " # [eye(3) [0 x y; 0 x y; 0 x y]]\n",
- " Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(\n",
- " (STATE_SIZE, LM_SIZE * calc_n_LM(x)))))\n",
- "\n",
- " jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],\n",
- " [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],\n",
- " [0.0, 0.0, 0.0]])\n",
- "\n",
- " G = np.eye(STATE_SIZE) + Fx.T * jF * Fx\n",
- " if calc_n_LM(x) > 0:\n",
- " print(Fx.shape)\n",
- " return G, Fx,\n",
- "\n",
- "\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 11,
- "metadata": {},
- "outputs": [],
- "source": [
- "def calc_LM_Pos(x, z):\n",
- " \"\"\"\n",
- " Calcualtes the pose in the world coordinate frame of a landmark at the given measurement. \n",
- "\n",
- " :param x: [x; y; theta]\n",
- " :param z: [range; bearing]\n",
- " :returns: [x; y] for given measurement\n",
- " \"\"\"\n",
- " zp = np.zeros((2, 1))\n",
- "\n",
- " zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1])\n",
- " zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1])\n",
- " #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])\n",
- " #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])\n",
- "\n",
- " return zp\n",
- "\n",
- "\n",
- "def get_LM_Pos_from_state(x, ind):\n",
- " \"\"\"\n",
- " Returns the position of a given landmark\n",
- " \n",
- " :param x: The state containing all landmark positions\n",
- " :param ind: landmark id\n",
- " :returns: The position of the landmark\n",
- " \"\"\"\n",
- " lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]\n",
- "\n",
- " return lm\n",
- "\n",
- "\n",
- "def search_correspond_LM_ID(xAug, PAug, zi):\n",
- " \"\"\"\n",
- " Landmark association with Mahalanobis distance.\n",
- " \n",
- " If this landmark is at least M_DIST_TH units away from all known landmarks, \n",
- " it is a NEW landmark.\n",
- " \n",
- " :param xAug: The estimated state\n",
- " :param PAug: The estimated covariance\n",
- " :param zi: the read measurements of specific landmark\n",
- " :returns: landmark id\n",
- " \"\"\"\n",
- "\n",
- " nLM = calc_n_LM(xAug)\n",
- "\n",
- " mdist = []\n",
- "\n",
- " for i in range(nLM):\n",
- " lm = get_LM_Pos_from_state(xAug, i)\n",
- " y, S, H = calc_innovation(lm, xAug, PAug, zi, i)\n",
- " mdist.append(y.T @ np.linalg.inv(S) @ y)\n",
- "\n",
- " mdist.append(M_DIST_TH) # new landmark\n",
- "\n",
- " minid = mdist.index(min(mdist))\n",
- "\n",
- " return minid\n",
- "\n",
- "def calc_input():\n",
- " v = 1.0 # [m/s]\n",
- " yawrate = 0.1 # [rad/s]\n",
- " u = np.array([[v, yawrate]]).T\n",
- " return u\n",
- "\n",
- "def pi_2_pi(angle):\n",
- " return (angle + math.pi) % (2 * math.pi) - math.pi"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 13,
- "metadata": {},
- "outputs": [],
- "source": [
- "def main():\n",
- " print(\" start!!\")\n",
- "\n",
- " time = 0.0\n",
- "\n",
- " # RFID positions [x, y]\n",
- " RFID = np.array([[10.0, -2.0],\n",
- " [15.0, 10.0],\n",
- " [3.0, 15.0],\n",
- " [-5.0, 20.0]])\n",
- "\n",
- " # State Vector [x y yaw v]'\n",
- " xEst = np.zeros((STATE_SIZE, 1))\n",
- " xTrue = np.zeros((STATE_SIZE, 1))\n",
- " PEst = np.eye(STATE_SIZE)\n",
- "\n",
- " xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning\n",
- "\n",
- " # history\n",
- " hxEst = xEst\n",
- " hxTrue = xTrue\n",
- " hxDR = xTrue\n",
- "\n",
- " while SIM_TIME >= time:\n",
- " time += DT\n",
- " u = calc_input()\n",
- "\n",
- " xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)\n",
- "\n",
- " xEst, PEst = ekf_slam(xEst, PEst, ud, z)\n",
- "\n",
- " x_state = xEst[0:STATE_SIZE]\n",
- "\n",
- " # store data history\n",
- " hxEst = np.hstack((hxEst, x_state))\n",
- " hxDR = np.hstack((hxDR, xDR))\n",
- " hxTrue = np.hstack((hxTrue, xTrue))\n",
- "\n",
- " if show_animation: # pragma: no cover\n",
- " plt.cla()\n",
- "\n",
- " plt.plot(RFID[:, 0], RFID[:, 1], \"*k\")\n",
- " plt.plot(xEst[0], xEst[1], \".r\")\n",
- "\n",
- " # plot landmark\n",
- " for i in range(calc_n_LM(xEst)):\n",
- " plt.plot(xEst[STATE_SIZE + i * 2],\n",
- " xEst[STATE_SIZE + i * 2 + 1], \"xg\")\n",
- "\n",
- " plt.plot(hxTrue[0, :],\n",
- " hxTrue[1, :], \"-b\")\n",
- " plt.plot(hxDR[0, :],\n",
- " hxDR[1, :], \"-k\")\n",
- " plt.plot(hxEst[0, :],\n",
- " hxEst[1, :], \"-r\")\n",
- " plt.axis(\"equal\")\n",
- " plt.grid(True)\n",
- " plt.pause(0.001)"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 20,
- "metadata": {
- "scrolled": false
- },
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- " start!!\n",
- "New LM\n",
- "New LM\n",
- "New LM\n"
- ]
- },
- {
- "data": {
- "application/javascript": [
- "/* Put everything inside the global mpl namespace */\n",
- "window.mpl = {};\n",
- "\n",
- "\n",
- "mpl.get_websocket_type = function() {\n",
- " if (typeof(WebSocket) !== 'undefined') {\n",
- " return WebSocket;\n",
- " } else if (typeof(MozWebSocket) !== 'undefined') {\n",
- " return MozWebSocket;\n",
- " } else {\n",
- " alert('Your browser does not have WebSocket support.' +\n",
- " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n",
- " 'Firefox 4 and 5 are also supported but you ' +\n",
- " 'have to enable WebSockets in about:config.');\n",
- " };\n",
- "}\n",
- "\n",
- "mpl.figure = function(figure_id, websocket, ondownload, parent_element) {\n",
- " this.id = figure_id;\n",
- "\n",
- " this.ws = websocket;\n",
- "\n",
- " this.supports_binary = (this.ws.binaryType != undefined);\n",
- "\n",
- " if (!this.supports_binary) {\n",
- " var warnings = document.getElementById(\"mpl-warnings\");\n",
- " if (warnings) {\n",
- " warnings.style.display = 'block';\n",
- " warnings.textContent = (\n",
- " \"This browser does not support binary websocket messages. \" +\n",
- " \"Performance may be slow.\");\n",
- " }\n",
- " }\n",
- "\n",
- " this.imageObj = new Image();\n",
- "\n",
- " this.context = undefined;\n",
- " this.message = undefined;\n",
- " this.canvas = undefined;\n",
- " this.rubberband_canvas = undefined;\n",
- " this.rubberband_context = undefined;\n",
- " this.format_dropdown = undefined;\n",
- "\n",
- " this.image_mode = 'full';\n",
- "\n",
- " this.root = $('
');\n",
- " this._root_extra_style(this.root)\n",
- " this.root.attr('style', 'display: inline-block');\n",
- "\n",
- " $(parent_element).append(this.root);\n",
- "\n",
- " this._init_header(this);\n",
- " this._init_canvas(this);\n",
- " this._init_toolbar(this);\n",
- "\n",
- " var fig = this;\n",
- "\n",
- " this.waiting = false;\n",
- "\n",
- " this.ws.onopen = function () {\n",
- " fig.send_message(\"supports_binary\", {value: fig.supports_binary});\n",
- " fig.send_message(\"send_image_mode\", {});\n",
- " if (mpl.ratio != 1) {\n",
- " fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.ratio});\n",
- " }\n",
- " fig.send_message(\"refresh\", {});\n",
- " }\n",
- "\n",
- " this.imageObj.onload = function() {\n",
- " if (fig.image_mode == 'full') {\n",
- " // Full images could contain transparency (where diff images\n",
- " // almost always do), so we need to clear the canvas so that\n",
- " // there is no ghosting.\n",
- " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n",
- " }\n",
- " fig.context.drawImage(fig.imageObj, 0, 0);\n",
- " };\n",
- "\n",
- " this.imageObj.onunload = function() {\n",
- " fig.ws.close();\n",
- " }\n",
- "\n",
- " this.ws.onmessage = this._make_on_message_function(this);\n",
- "\n",
- " this.ondownload = ondownload;\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._init_header = function() {\n",
- " var titlebar = $(\n",
- " '
');\n",
- " var titletext = $(\n",
- " '
');\n",
- " titlebar.append(titletext)\n",
- " this.root.append(titlebar);\n",
- " this.header = titletext[0];\n",
- "}\n",
- "\n",
- "\n",
- "\n",
- "mpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n",
- "\n",
- "}\n",
- "\n",
- "\n",
- "mpl.figure.prototype._root_extra_style = function(canvas_div) {\n",
- "\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._init_canvas = function() {\n",
- " var fig = this;\n",
- "\n",
- " var canvas_div = $('
');\n",
- "\n",
- " canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n",
- "\n",
- " function canvas_keyboard_event(event) {\n",
- " return fig.key_event(event, event['data']);\n",
- " }\n",
- "\n",
- " canvas_div.keydown('key_press', canvas_keyboard_event);\n",
- " canvas_div.keyup('key_release', canvas_keyboard_event);\n",
- " this.canvas_div = canvas_div\n",
- " this._canvas_extra_style(canvas_div)\n",
- " this.root.append(canvas_div);\n",
- "\n",
- " var canvas = $(' ');\n",
- " canvas.addClass('mpl-canvas');\n",
- " canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n",
- "\n",
- " this.canvas = canvas[0];\n",
- " this.context = canvas[0].getContext(\"2d\");\n",
- "\n",
- " var backingStore = this.context.backingStorePixelRatio ||\n",
- "\tthis.context.webkitBackingStorePixelRatio ||\n",
- "\tthis.context.mozBackingStorePixelRatio ||\n",
- "\tthis.context.msBackingStorePixelRatio ||\n",
- "\tthis.context.oBackingStorePixelRatio ||\n",
- "\tthis.context.backingStorePixelRatio || 1;\n",
- "\n",
- " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n",
- "\n",
- " var rubberband = $(' ');\n",
- " rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n",
- "\n",
- " var pass_mouse_events = true;\n",
- "\n",
- " canvas_div.resizable({\n",
- " start: function(event, ui) {\n",
- " pass_mouse_events = false;\n",
- " },\n",
- " resize: function(event, ui) {\n",
- " fig.request_resize(ui.size.width, ui.size.height);\n",
- " },\n",
- " stop: function(event, ui) {\n",
- " pass_mouse_events = true;\n",
- " fig.request_resize(ui.size.width, ui.size.height);\n",
- " },\n",
- " });\n",
- "\n",
- " function mouse_event_fn(event) {\n",
- " if (pass_mouse_events)\n",
- " return fig.mouse_event(event, event['data']);\n",
- " }\n",
- "\n",
- " rubberband.mousedown('button_press', mouse_event_fn);\n",
- " rubberband.mouseup('button_release', mouse_event_fn);\n",
- " // Throttle sequential mouse events to 1 every 20ms.\n",
- " rubberband.mousemove('motion_notify', mouse_event_fn);\n",
- "\n",
- " rubberband.mouseenter('figure_enter', mouse_event_fn);\n",
- " rubberband.mouseleave('figure_leave', mouse_event_fn);\n",
- "\n",
- " canvas_div.on(\"wheel\", function (event) {\n",
- " event = event.originalEvent;\n",
- " event['data'] = 'scroll'\n",
- " if (event.deltaY < 0) {\n",
- " event.step = 1;\n",
- " } else {\n",
- " event.step = -1;\n",
- " }\n",
- " mouse_event_fn(event);\n",
- " });\n",
- "\n",
- " canvas_div.append(canvas);\n",
- " canvas_div.append(rubberband);\n",
- "\n",
- " this.rubberband = rubberband;\n",
- " this.rubberband_canvas = rubberband[0];\n",
- " this.rubberband_context = rubberband[0].getContext(\"2d\");\n",
- " this.rubberband_context.strokeStyle = \"#000000\";\n",
- "\n",
- " this._resize_canvas = function(width, height) {\n",
- " // Keep the size of the canvas, canvas container, and rubber band\n",
- " // canvas in synch.\n",
- " canvas_div.css('width', width)\n",
- " canvas_div.css('height', height)\n",
- "\n",
- " canvas.attr('width', width * mpl.ratio);\n",
- " canvas.attr('height', height * mpl.ratio);\n",
- " canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n",
- "\n",
- " rubberband.attr('width', width);\n",
- " rubberband.attr('height', height);\n",
- " }\n",
- "\n",
- " // Set the figure to an initial 600x600px, this will subsequently be updated\n",
- " // upon first draw.\n",
- " this._resize_canvas(600, 600);\n",
- "\n",
- " // Disable right mouse context menu.\n",
- " $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\n",
- " return false;\n",
- " });\n",
- "\n",
- " function set_focus () {\n",
- " canvas.focus();\n",
- " canvas_div.focus();\n",
- " }\n",
- "\n",
- " window.setTimeout(set_focus, 100);\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._init_toolbar = function() {\n",
- " var fig = this;\n",
- "\n",
- " var nav_element = $('
')\n",
- " nav_element.attr('style', 'width: 100%');\n",
- " this.root.append(nav_element);\n",
- "\n",
- " // Define a callback function for later on.\n",
- " function toolbar_event(event) {\n",
- " return fig.toolbar_button_onclick(event['data']);\n",
- " }\n",
- " function toolbar_mouse_event(event) {\n",
- " return fig.toolbar_button_onmouseover(event['data']);\n",
- " }\n",
- "\n",
- " for(var toolbar_ind in mpl.toolbar_items) {\n",
- " var name = mpl.toolbar_items[toolbar_ind][0];\n",
- " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n",
- " var image = mpl.toolbar_items[toolbar_ind][2];\n",
- " var method_name = mpl.toolbar_items[toolbar_ind][3];\n",
- "\n",
- " if (!name) {\n",
- " // put a spacer in here.\n",
- " continue;\n",
- " }\n",
- " var button = $(' ');\n",
- " button.addClass('ui-button ui-widget ui-state-default ui-corner-all ' +\n",
- " 'ui-button-icon-only');\n",
- " button.attr('role', 'button');\n",
- " button.attr('aria-disabled', 'false');\n",
- " button.click(method_name, toolbar_event);\n",
- " button.mouseover(tooltip, toolbar_mouse_event);\n",
- "\n",
- " var icon_img = $(' ');\n",
- " icon_img.addClass('ui-button-icon-primary ui-icon');\n",
- " icon_img.addClass(image);\n",
- " icon_img.addClass('ui-corner-all');\n",
- "\n",
- " var tooltip_span = $(' ');\n",
- " tooltip_span.addClass('ui-button-text');\n",
- " tooltip_span.html(tooltip);\n",
- "\n",
- " button.append(icon_img);\n",
- " button.append(tooltip_span);\n",
- "\n",
- " nav_element.append(button);\n",
- " }\n",
- "\n",
- " var fmt_picker_span = $(' ');\n",
- "\n",
- " var fmt_picker = $(' ');\n",
- " fmt_picker.addClass('mpl-toolbar-option ui-widget ui-widget-content');\n",
- " fmt_picker_span.append(fmt_picker);\n",
- " nav_element.append(fmt_picker_span);\n",
- " this.format_dropdown = fmt_picker[0];\n",
- "\n",
- " for (var ind in mpl.extensions) {\n",
- " var fmt = mpl.extensions[ind];\n",
- " var option = $(\n",
- " ' ', {selected: fmt === mpl.default_extension}).html(fmt);\n",
- " fmt_picker.append(option)\n",
- " }\n",
- "\n",
- " // Add hover states to the ui-buttons\n",
- " $( \".ui-button\" ).hover(\n",
- " function() { $(this).addClass(\"ui-state-hover\");},\n",
- " function() { $(this).removeClass(\"ui-state-hover\");}\n",
- " );\n",
- "\n",
- " var status_bar = $('');\n",
- " nav_element.append(status_bar);\n",
- " this.message = status_bar[0];\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.request_resize = function(x_pixels, y_pixels) {\n",
- " // Request matplotlib to resize the figure. Matplotlib will then trigger a resize in the client,\n",
- " // which will in turn request a refresh of the image.\n",
- " this.send_message('resize', {'width': x_pixels, 'height': y_pixels});\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.send_message = function(type, properties) {\n",
- " properties['type'] = type;\n",
- " properties['figure_id'] = this.id;\n",
- " this.ws.send(JSON.stringify(properties));\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.send_draw_message = function() {\n",
- " if (!this.waiting) {\n",
- " this.waiting = true;\n",
- " this.ws.send(JSON.stringify({type: \"draw\", figure_id: this.id}));\n",
- " }\n",
- "}\n",
- "\n",
- "\n",
- "mpl.figure.prototype.handle_save = function(fig, msg) {\n",
- " var format_dropdown = fig.format_dropdown;\n",
- " var format = format_dropdown.options[format_dropdown.selectedIndex].value;\n",
- " fig.ondownload(fig, format);\n",
- "}\n",
- "\n",
- "\n",
- "mpl.figure.prototype.handle_resize = function(fig, msg) {\n",
- " var size = msg['size'];\n",
- " if (size[0] != fig.canvas.width || size[1] != fig.canvas.height) {\n",
- " fig._resize_canvas(size[0], size[1]);\n",
- " fig.send_message(\"refresh\", {});\n",
- " };\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_rubberband = function(fig, msg) {\n",
- " var x0 = msg['x0'] / mpl.ratio;\n",
- " var y0 = (fig.canvas.height - msg['y0']) / mpl.ratio;\n",
- " var x1 = msg['x1'] / mpl.ratio;\n",
- " var y1 = (fig.canvas.height - msg['y1']) / mpl.ratio;\n",
- " x0 = Math.floor(x0) + 0.5;\n",
- " y0 = Math.floor(y0) + 0.5;\n",
- " x1 = Math.floor(x1) + 0.5;\n",
- " y1 = Math.floor(y1) + 0.5;\n",
- " var min_x = Math.min(x0, x1);\n",
- " var min_y = Math.min(y0, y1);\n",
- " var width = Math.abs(x1 - x0);\n",
- " var height = Math.abs(y1 - y0);\n",
- "\n",
- " fig.rubberband_context.clearRect(\n",
- " 0, 0, fig.canvas.width, fig.canvas.height);\n",
- "\n",
- " fig.rubberband_context.strokeRect(min_x, min_y, width, height);\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_figure_label = function(fig, msg) {\n",
- " // Updates the figure title.\n",
- " fig.header.textContent = msg['label'];\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_cursor = function(fig, msg) {\n",
- " var cursor = msg['cursor'];\n",
- " switch(cursor)\n",
- " {\n",
- " case 0:\n",
- " cursor = 'pointer';\n",
- " break;\n",
- " case 1:\n",
- " cursor = 'default';\n",
- " break;\n",
- " case 2:\n",
- " cursor = 'crosshair';\n",
- " break;\n",
- " case 3:\n",
- " cursor = 'move';\n",
- " break;\n",
- " }\n",
- " fig.rubberband_canvas.style.cursor = cursor;\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_message = function(fig, msg) {\n",
- " fig.message.textContent = msg['message'];\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_draw = function(fig, msg) {\n",
- " // Request the server to send over a new figure.\n",
- " fig.send_draw_message();\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_image_mode = function(fig, msg) {\n",
- " fig.image_mode = msg['mode'];\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.updated_canvas_event = function() {\n",
- " // Called whenever the canvas gets updated.\n",
- " this.send_message(\"ack\", {});\n",
- "}\n",
- "\n",
- "// A function to construct a web socket function for onmessage handling.\n",
- "// Called in the figure constructor.\n",
- "mpl.figure.prototype._make_on_message_function = function(fig) {\n",
- " return function socket_on_message(evt) {\n",
- " if (evt.data instanceof Blob) {\n",
- " /* FIXME: We get \"Resource interpreted as Image but\n",
- " * transferred with MIME type text/plain:\" errors on\n",
- " * Chrome. But how to set the MIME type? It doesn't seem\n",
- " * to be part of the websocket stream */\n",
- " evt.data.type = \"image/png\";\n",
- "\n",
- " /* Free the memory for the previous frames */\n",
- " if (fig.imageObj.src) {\n",
- " (window.URL || window.webkitURL).revokeObjectURL(\n",
- " fig.imageObj.src);\n",
- " }\n",
- "\n",
- " fig.imageObj.src = (window.URL || window.webkitURL).createObjectURL(\n",
- " evt.data);\n",
- " fig.updated_canvas_event();\n",
- " fig.waiting = false;\n",
- " return;\n",
- " }\n",
- " else if (typeof evt.data === 'string' && evt.data.slice(0, 21) == \"data:image/png;base64\") {\n",
- " fig.imageObj.src = evt.data;\n",
- " fig.updated_canvas_event();\n",
- " fig.waiting = false;\n",
- " return;\n",
- " }\n",
- "\n",
- " var msg = JSON.parse(evt.data);\n",
- " var msg_type = msg['type'];\n",
- "\n",
- " // Call the \"handle_{type}\" callback, which takes\n",
- " // the figure and JSON message as its only arguments.\n",
- " try {\n",
- " var callback = fig[\"handle_\" + msg_type];\n",
- " } catch (e) {\n",
- " console.log(\"No handler for the '\" + msg_type + \"' message type: \", msg);\n",
- " return;\n",
- " }\n",
- "\n",
- " if (callback) {\n",
- " try {\n",
- " // console.log(\"Handling '\" + msg_type + \"' message: \", msg);\n",
- " callback(fig, msg);\n",
- " } catch (e) {\n",
- " console.log(\"Exception inside the 'handler_\" + msg_type + \"' callback:\", e, e.stack, msg);\n",
- " }\n",
- " }\n",
- " };\n",
- "}\n",
- "\n",
- "// from http://stackoverflow.com/questions/1114465/getting-mouse-location-in-canvas\n",
- "mpl.findpos = function(e) {\n",
- " //this section is from http://www.quirksmode.org/js/events_properties.html\n",
- " var targ;\n",
- " if (!e)\n",
- " e = window.event;\n",
- " if (e.target)\n",
- " targ = e.target;\n",
- " else if (e.srcElement)\n",
- " targ = e.srcElement;\n",
- " if (targ.nodeType == 3) // defeat Safari bug\n",
- " targ = targ.parentNode;\n",
- "\n",
- " // jQuery normalizes the pageX and pageY\n",
- " // pageX,Y are the mouse positions relative to the document\n",
- " // offset() returns the position of the element relative to the document\n",
- " var x = e.pageX - $(targ).offset().left;\n",
- " var y = e.pageY - $(targ).offset().top;\n",
- "\n",
- " return {\"x\": x, \"y\": y};\n",
- "};\n",
- "\n",
- "/*\n",
- " * return a copy of an object with only non-object keys\n",
- " * we need this to avoid circular references\n",
- " * http://stackoverflow.com/a/24161582/3208463\n",
- " */\n",
- "function simpleKeys (original) {\n",
- " return Object.keys(original).reduce(function (obj, key) {\n",
- " if (typeof original[key] !== 'object')\n",
- " obj[key] = original[key]\n",
- " return obj;\n",
- " }, {});\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.mouse_event = function(event, name) {\n",
- " var canvas_pos = mpl.findpos(event)\n",
- "\n",
- " if (name === 'button_press')\n",
- " {\n",
- " this.canvas.focus();\n",
- " this.canvas_div.focus();\n",
- " }\n",
- "\n",
- " var x = canvas_pos.x * mpl.ratio;\n",
- " var y = canvas_pos.y * mpl.ratio;\n",
- "\n",
- " this.send_message(name, {x: x, y: y, button: event.button,\n",
- " step: event.step,\n",
- " guiEvent: simpleKeys(event)});\n",
- "\n",
- " /* This prevents the web browser from automatically changing to\n",
- " * the text insertion cursor when the button is pressed. We want\n",
- " * to control all of the cursor setting manually through the\n",
- " * 'cursor' event from matplotlib */\n",
- " event.preventDefault();\n",
- " return false;\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._key_event_extra = function(event, name) {\n",
- " // Handle any extra behaviour associated with a key event\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.key_event = function(event, name) {\n",
- "\n",
- " // Prevent repeat events\n",
- " if (name == 'key_press')\n",
- " {\n",
- " if (event.which === this._key)\n",
- " return;\n",
- " else\n",
- " this._key = event.which;\n",
- " }\n",
- " if (name == 'key_release')\n",
- " this._key = null;\n",
- "\n",
- " var value = '';\n",
- " if (event.ctrlKey && event.which != 17)\n",
- " value += \"ctrl+\";\n",
- " if (event.altKey && event.which != 18)\n",
- " value += \"alt+\";\n",
- " if (event.shiftKey && event.which != 16)\n",
- " value += \"shift+\";\n",
- "\n",
- " value += 'k';\n",
- " value += event.which.toString();\n",
- "\n",
- " this._key_event_extra(event, name);\n",
- "\n",
- " this.send_message(name, {key: value,\n",
- " guiEvent: simpleKeys(event)});\n",
- " return false;\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.toolbar_button_onclick = function(name) {\n",
- " if (name == 'download') {\n",
- " this.handle_save(this, null);\n",
- " } else {\n",
- " this.send_message(\"toolbar_button\", {name: name});\n",
- " }\n",
- "};\n",
- "\n",
- "mpl.figure.prototype.toolbar_button_onmouseover = function(tooltip) {\n",
- " this.message.textContent = tooltip;\n",
- "};\n",
- "mpl.toolbar_items = [[\"Home\", \"Reset original view\", \"fa fa-home icon-home\", \"home\"], [\"Back\", \"Back to previous view\", \"fa fa-arrow-left icon-arrow-left\", \"back\"], [\"Forward\", \"Forward to next view\", \"fa fa-arrow-right icon-arrow-right\", \"forward\"], [\"\", \"\", \"\", \"\"], [\"Pan\", \"Pan axes with left mouse, zoom with right\", \"fa fa-arrows icon-move\", \"pan\"], [\"Zoom\", \"Zoom to rectangle\", \"fa fa-square-o icon-check-empty\", \"zoom\"], [\"\", \"\", \"\", \"\"], [\"Download\", \"Download plot\", \"fa fa-floppy-o icon-save\", \"download\"]];\n",
- "\n",
- "mpl.extensions = [\"eps\", \"pdf\", \"png\", \"ps\", \"raw\", \"svg\"];\n",
- "\n",
- "mpl.default_extension = \"png\";var comm_websocket_adapter = function(comm) {\n",
- " // Create a \"websocket\"-like object which calls the given IPython comm\n",
- " // object with the appropriate methods. Currently this is a non binary\n",
- " // socket, so there is still some room for performance tuning.\n",
- " var ws = {};\n",
- "\n",
- " ws.close = function() {\n",
- " comm.close()\n",
- " };\n",
- " ws.send = function(m) {\n",
- " //console.log('sending', m);\n",
- " comm.send(m);\n",
- " };\n",
- " // Register the callback with on_msg.\n",
- " comm.on_msg(function(msg) {\n",
- " //console.log('receiving', msg['content']['data'], msg);\n",
- " // Pass the mpl event to the overridden (by mpl) onmessage function.\n",
- " ws.onmessage(msg['content']['data'])\n",
- " });\n",
- " return ws;\n",
- "}\n",
- "\n",
- "mpl.mpl_figure_comm = function(comm, msg) {\n",
- " // This is the function which gets called when the mpl process\n",
- " // starts-up an IPython Comm through the \"matplotlib\" channel.\n",
- "\n",
- " var id = msg.content.data.id;\n",
- " // Get hold of the div created by the display call when the Comm\n",
- " // socket was opened in Python.\n",
- " var element = $(\"#\" + id);\n",
- " var ws_proxy = comm_websocket_adapter(comm)\n",
- "\n",
- " function ondownload(figure, format) {\n",
- " window.open(figure.imageObj.src);\n",
- " }\n",
- "\n",
- " var fig = new mpl.figure(id, ws_proxy,\n",
- " ondownload,\n",
- " element.get(0));\n",
- "\n",
- " // Call onopen now - mpl needs it, as it is assuming we've passed it a real\n",
- " // web socket which is closed, not our websocket->open comm proxy.\n",
- " ws_proxy.onopen();\n",
- "\n",
- " fig.parent_element = element.get(0);\n",
- " fig.cell_info = mpl.find_output_cell(\"
\");\n",
- " if (!fig.cell_info) {\n",
- " console.error(\"Failed to find cell for figure\", id, fig);\n",
- " return;\n",
- " }\n",
- "\n",
- " var output_index = fig.cell_info[2]\n",
- " var cell = fig.cell_info[0];\n",
- "\n",
- "};\n",
- "\n",
- "mpl.figure.prototype.handle_close = function(fig, msg) {\n",
- " var width = fig.canvas.width/mpl.ratio\n",
- " fig.root.unbind('remove')\n",
- "\n",
- " // Update the output cell to use the data from the current canvas.\n",
- " fig.push_to_output();\n",
- " var dataURL = fig.canvas.toDataURL();\n",
- " // Re-enable the keyboard manager in IPython - without this line, in FF,\n",
- " // the notebook keyboard shortcuts fail.\n",
- " IPython.keyboard_manager.enable()\n",
- " $(fig.parent_element).html(' ');\n",
- " fig.close_ws(fig, msg);\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.close_ws = function(fig, msg){\n",
- " fig.send_message('closing', msg);\n",
- " // fig.ws.close()\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.push_to_output = function(remove_interactive) {\n",
- " // Turn the data on the canvas into data in the output cell.\n",
- " var width = this.canvas.width/mpl.ratio\n",
- " var dataURL = this.canvas.toDataURL();\n",
- " this.cell_info[1]['text/html'] = ' ';\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.updated_canvas_event = function() {\n",
- " // Tell IPython that the notebook contents must change.\n",
- " IPython.notebook.set_dirty(true);\n",
- " this.send_message(\"ack\", {});\n",
- " var fig = this;\n",
- " // Wait a second, then push the new image to the DOM so\n",
- " // that it is saved nicely (might be nice to debounce this).\n",
- " setTimeout(function () { fig.push_to_output() }, 1000);\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._init_toolbar = function() {\n",
- " var fig = this;\n",
- "\n",
- " var nav_element = $('
')\n",
- " nav_element.attr('style', 'width: 100%');\n",
- " this.root.append(nav_element);\n",
- "\n",
- " // Define a callback function for later on.\n",
- " function toolbar_event(event) {\n",
- " return fig.toolbar_button_onclick(event['data']);\n",
- " }\n",
- " function toolbar_mouse_event(event) {\n",
- " return fig.toolbar_button_onmouseover(event['data']);\n",
- " }\n",
- "\n",
- " for(var toolbar_ind in mpl.toolbar_items){\n",
- " var name = mpl.toolbar_items[toolbar_ind][0];\n",
- " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n",
- " var image = mpl.toolbar_items[toolbar_ind][2];\n",
- " var method_name = mpl.toolbar_items[toolbar_ind][3];\n",
- "\n",
- " if (!name) { continue; };\n",
- "\n",
- " var button = $(' ');\n",
- " button.click(method_name, toolbar_event);\n",
- " button.mouseover(tooltip, toolbar_mouse_event);\n",
- " nav_element.append(button);\n",
- " }\n",
- "\n",
- " // Add the status bar.\n",
- " var status_bar = $(' ');\n",
- " nav_element.append(status_bar);\n",
- " this.message = status_bar[0];\n",
- "\n",
- " // Add the close button to the window.\n",
- " var buttongrp = $('
');\n",
- " var button = $(' ');\n",
- " button.click(function (evt) { fig.handle_close(fig, {}); } );\n",
- " button.mouseover('Stop Interaction', toolbar_mouse_event);\n",
- " buttongrp.append(button);\n",
- " var titlebar = this.root.find($('.ui-dialog-titlebar'));\n",
- " titlebar.prepend(buttongrp);\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._root_extra_style = function(el){\n",
- " var fig = this\n",
- " el.on(\"remove\", function(){\n",
- "\tfig.close_ws(fig, {});\n",
- " });\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._canvas_extra_style = function(el){\n",
- " // this is important to make the div 'focusable\n",
- " el.attr('tabindex', 0)\n",
- " // reach out to IPython and tell the keyboard manager to turn it's self\n",
- " // off when our div gets focus\n",
- "\n",
- " // location in version 3\n",
- " if (IPython.notebook.keyboard_manager) {\n",
- " IPython.notebook.keyboard_manager.register_events(el);\n",
- " }\n",
- " else {\n",
- " // location in version 2\n",
- " IPython.keyboard_manager.register_events(el);\n",
- " }\n",
- "\n",
- "}\n",
- "\n",
- "mpl.figure.prototype._key_event_extra = function(event, name) {\n",
- " var manager = IPython.notebook.keyboard_manager;\n",
- " if (!manager)\n",
- " manager = IPython.keyboard_manager;\n",
- "\n",
- " // Check for shift+enter\n",
- " if (event.shiftKey && event.which == 13) {\n",
- " this.canvas_div.blur();\n",
- " event.shiftKey = false;\n",
- " // Send a \"J\" for go to next cell\n",
- " event.which = 74;\n",
- " event.keyCode = 74;\n",
- " manager.command_mode();\n",
- " manager.handle_keydown(event);\n",
- " }\n",
- "}\n",
- "\n",
- "mpl.figure.prototype.handle_save = function(fig, msg) {\n",
- " fig.ondownload(fig, null);\n",
- "}\n",
- "\n",
- "\n",
- "mpl.find_output_cell = function(html_output) {\n",
- " // Return the cell and output element which can be found *uniquely* in the notebook.\n",
- " // Note - this is a bit hacky, but it is done because the \"notebook_saving.Notebook\"\n",
- " // IPython event is triggered only after the cells have been serialised, which for\n",
- " // our purposes (turning an active figure into a static one), is too late.\n",
- " var cells = IPython.notebook.get_cells();\n",
- " var ncells = cells.length;\n",
- " for (var i=0; i= 3 moved mimebundle to data attribute of output\n",
- " data = data.data;\n",
- " }\n",
- " if (data['text/html'] == html_output) {\n",
- " return [cell, data, j];\n",
- " }\n",
- " }\n",
- " }\n",
- " }\n",
- "}\n",
- "\n",
- "// Register the function which deals with the matplotlib target/channel.\n",
- "// The kernel may be null if the page has been refreshed.\n",
- "if (IPython.notebook.kernel != null) {\n",
- " IPython.notebook.kernel.comm_manager.register_target('matplotlib', mpl.mpl_figure_comm);\n",
- "}\n"
- ],
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- },
- {
- "data": {
- "text/html": [
- " "
- ],
- "text/plain": [
- ""
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- },
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "New LM\n"
- ]
- }
- ],
- "source": [
- "%matplotlib notebook\n",
- "%matplotlib notebook\n",
- "main()"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.1"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py
index de1b94ec8f..5c4417d7c3 100644
--- a/SLAM/EKFSLAM/ekf_slam.py
+++ b/SLAM/EKFSLAM/ekf_slam.py
@@ -1,19 +1,21 @@
"""
Extended Kalman Filter SLAM example
+
author: Atsushi Sakai (@Atsushi_twi)
"""
import math
-import numpy as np
-import matplotlib.pyplot as plt
+import matplotlib.pyplot as plt
+import numpy as np
+from utils.angle import angle_mod
# EKF state covariance
-Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2
+Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)]) ** 2
# Simulation parameter
-Qsim = np.diag([0.2, np.deg2rad(1.0)])**2
-Rsim = np.diag([1.0, np.deg2rad(10.0)])**2
+Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2
+R_sim = np.diag([1.0, np.deg2rad(10.0)]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
@@ -26,29 +28,27 @@
def ekf_slam(xEst, PEst, u, z):
-
# Predict
- S = STATE_SIZE
- xEst[0:S] = motion_model(xEst[0:S], u)
- G, Fx = jacob_motion(xEst[0:S], u)
- PEst[0:S, 0:S] = G.T * PEst[0:S, 0:S] * G + Fx.T * Cx * Fx
+ G, Fx = jacob_motion(xEst, u)
+ xEst[0:STATE_SIZE] = motion_model(xEst[0:STATE_SIZE], u)
+ PEst = G.T @ PEst @ G + Fx.T @ Cx @ Fx
initP = np.eye(2)
# Update
for iz in range(len(z[:, 0])): # for each observation
- minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2])
+ min_id = search_correspond_landmark_id(xEst, PEst, z[iz, 0:2])
- nLM = calc_n_LM(xEst)
- if minid == nLM:
+ nLM = calc_n_lm(xEst)
+ if min_id == nLM:
print("New LM")
# Extend state and covariance matrix
- xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :])))
+ xAug = np.vstack((xEst, calc_landmark_position(xEst, z[iz, :])))
PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),
np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))
xEst = xAug
PEst = PAug
- lm = get_LM_Pos_from_state(xEst, minid)
- y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid)
+ lm = get_landmark_position_from_state(xEst, min_id)
+ y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], min_id)
K = (PEst @ H.T) @ np.linalg.inv(S)
xEst = xEst + (K @ y)
@@ -61,13 +61,12 @@ def ekf_slam(xEst, PEst, u, z):
def calc_input():
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
- u = np.array([[v, yawrate]]).T
+ yaw_rate = 0.1 # [rad/s]
+ u = np.array([[v, yaw_rate]]).T
return u
def observation(xTrue, xd, u, RFID):
-
xTrue = motion_model(xTrue, u)
# add noise to gps x-y
@@ -77,25 +76,24 @@ def observation(xTrue, xd, u, RFID):
dx = RFID[i, 0] - xTrue[0, 0]
dy = RFID[i, 1] - xTrue[1, 0]
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
- zi = np.array([dn, anglen, i])
+ dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise
+ angle_n = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise
+ zi = np.array([dn, angle_n, i])
z = np.vstack((z, zi))
# add noise to input
ud = np.array([[
- u[0, 0] + np.random.randn() * Rsim[0, 0],
- u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T
+ u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5,
+ u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T
xd = motion_model(xd, ud)
return xTrue, z, xd, ud
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0],
[0, 1.0, 0],
[0, 0, 1.0]])
@@ -108,84 +106,80 @@ def motion_model(x, u):
return x
-def calc_n_LM(x):
+def calc_n_lm(x):
n = int((len(x) - STATE_SIZE) / LM_SIZE)
return n
def jacob_motion(x, u):
-
Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(
- (STATE_SIZE, LM_SIZE * calc_n_LM(x)))))
+ (STATE_SIZE, LM_SIZE * calc_n_lm(x)))))
- jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],
- [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],
- [0.0, 0.0, 0.0]])
+ jF = np.array([[0.0, 0.0, -DT * u[0, 0] * math.sin(x[2, 0])],
+ [0.0, 0.0, DT * u[0, 0] * math.cos(x[2, 0])],
+ [0.0, 0.0, 0.0]], dtype=float)
- G = np.eye(STATE_SIZE) + Fx.T * jF * Fx
+ G = np.eye(len(x)) + Fx.T @ jF @ Fx
return G, Fx,
-def calc_LM_Pos(x, z):
+def calc_landmark_position(x, z):
zp = np.zeros((2, 1))
zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1])
zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1])
- #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])
- #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])
return zp
-def get_LM_Pos_from_state(x, ind):
-
+def get_landmark_position_from_state(x, ind):
lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]
return lm
-def search_correspond_LM_ID(xAug, PAug, zi):
+def search_correspond_landmark_id(xAug, PAug, zi):
"""
Landmark association with Mahalanobis distance
"""
- nLM = calc_n_LM(xAug)
+ nLM = calc_n_lm(xAug)
- mdist = []
+ min_dist = []
for i in range(nLM):
- lm = get_LM_Pos_from_state(xAug, i)
+ lm = get_landmark_position_from_state(xAug, i)
y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
- mdist.append(y.T @ np.linalg.inv(S) @ y)
+ min_dist.append(y.T @ np.linalg.inv(S) @ y)
- mdist.append(M_DIST_TH) # new landmark
+ min_dist.append(M_DIST_TH) # new landmark
- minid = mdist.index(min(mdist))
+ min_id = min_dist.index(min(min_dist))
- return minid
+ return min_id
def calc_innovation(lm, xEst, PEst, z, LMid):
delta = lm - xEst[0:2]
q = (delta.T @ delta)[0, 0]
- zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]
- zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]])
+ z_angle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]
+ zp = np.array([[math.sqrt(q), pi_2_pi(z_angle)]])
y = (z - zp).T
y[1] = pi_2_pi(y[1])
- H = jacobH(q, delta, xEst, LMid + 1)
+ H = jacob_h(q, delta, xEst, LMid + 1)
S = H @ PEst @ H.T + Cx[0:2, 0:2]
return y, S, H
-def jacobH(q, delta, x, i):
+def jacob_h(q, delta, x, i):
sq = math.sqrt(q)
G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],
- [delta[1, 0], - delta[0, 0], - 1.0, - delta[1, 0], delta[0, 0]]])
+ [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]])
G = G / q
- nLM = calc_n_LM(x)
+ nLM = calc_n_lm(x)
F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),
np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
@@ -198,7 +192,7 @@ def jacobH(q, delta, x, i):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def main():
@@ -241,12 +235,16 @@ def main():
if show_animation: # pragma: no cover
plt.cla()
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
plt.plot(xEst[0], xEst[1], ".r")
# plot landmark
- for i in range(calc_n_LM(xEst)):
+ for i in range(calc_n_lm(xEst)):
plt.plot(xEst[STATE_SIZE + i * 2],
xEst[STATE_SIZE + i * 2 + 1], "xg")
@@ -262,4 +260,4 @@ def main():
if __name__ == '__main__':
- main()
\ No newline at end of file
+ main()
diff --git a/SLAM/FastSLAM1/FastSLAM1.ipynb b/SLAM/FastSLAM1/FastSLAM1.ipynb
deleted file mode 100644
index 9ce48238f9..0000000000
--- a/SLAM/FastSLAM1/FastSLAM1.ipynb
+++ /dev/null
@@ -1,676 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## FastSLAM1.0"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "execution_count": 1,
- "metadata": {
- "image/png": {
- "width": 600
- }
- },
- "output_type": "execute_result"
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"animation.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Simulation\n",
- "\n",
- "This is a feature based SLAM example using FastSLAM 1.0.\n",
- "\n",
- "The blue line is ground truth, the black line is dead reckoning, the red\n",
- "line is the estimated trajectory with FastSLAM.\n",
- "\n",
- "The red points are particles of FastSLAM.\n",
- "\n",
- "Black points are landmarks, blue crosses are estimated landmark\n",
- "positions by FastSLAM.\n",
- "\n",
- "\n",
- ""
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Introduction\n",
- "\n",
- "FastSLAM algorithm implementation is based on particle filters and belongs to the family of probabilistic SLAM approaches. It is used with feature-based maps (see gif above) or with occupancy grid maps.\n",
- "\n",
- "As it is shown, the particle filter differs from EKF by representing the robot's estimation through a set of particles. Each single particle has an independent belief, as it holds the pose $(x, y, \\theta)$ and an array of landmark locations $[(x_1, y_1), (x_2, y_2), ... (x_n, y_n)]$ for n landmarks.\n",
- "\n",
- "* The blue line is the true trajectory\n",
- "* The red line is the estimated trajectory\n",
- "* The red dots represent the distribution of particles\n",
- "* The black line represent dead reckoning tracjectory\n",
- "* The blue x is the observed and estimated landmarks\n",
- "* The black x is the true landmark\n",
- "\n",
- "I.e. Each particle maintains a deterministic pose and n-EKFs for each landmark and update it with each measurement."
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Algorithm walkthrough\n",
- "\n",
- "The particles are initially drawn from a uniform distribution the represent the initial uncertainty.\n",
- "At each time step we do:\n",
- "\n",
- "* Predict the pose for each particle by using $u$ and the motion model (the landmarks are not updated). \n",
- "* Update the particles with observations $z$, where the weights are adjusted based on how likely the particle to have the correct pose given the sensor measurement\n",
- "* Resampling such that the particles with the largest weights survive and the unlikely ones with the lowest weights die out.\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### 1- Predict\n",
- "The following equations and code snippets we can see how the particles distribution evolves in case we provide only the control $(v,w)$, which are the linear and angular velocity repsectively. \n",
- "\n",
- "$\\begin{equation*}\n",
- "F=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 \\\\\n",
- "0 & 1 & 0 \\\\\n",
- "0 & 0 & 1 \n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "B=\n",
- "\\begin{bmatrix}\n",
- "\\Delta t cos(\\theta) & 0\\\\\n",
- "\\Delta t sin(\\theta) & 0\\\\\n",
- "0 & \\Delta t\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n",
- "$\\begin{equation*}\n",
- "X = FX + BU \n",
- "\\end{equation*}$\n",
- "\n",
- "\n",
- "$\\begin{equation*}\n",
- "\\begin{bmatrix}\n",
- "x_{t+1} \\\\\n",
- "y_{t+1} \\\\\n",
- "\\theta_{t+1}\n",
- "\\end{bmatrix}=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 \\\\\n",
- "0 & 1 & 0 \\\\\n",
- "0 & 0 & 1 \n",
- "\\end{bmatrix}\\begin{bmatrix}\n",
- "x_{t} \\\\\n",
- "y_{t} \\\\\n",
- "\\theta_{t}\n",
- "\\end{bmatrix}+\n",
- "\\begin{bmatrix}\n",
- "\\Delta t cos(\\theta) & 0\\\\\n",
- "\\Delta t sin(\\theta) & 0\\\\\n",
- "0 & \\Delta t\n",
- "\\end{bmatrix}\n",
- "\\begin{bmatrix}\n",
- "v_{t} + \\sigma_v\\\\\n",
- "w_{t} + \\sigma_w\\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$\n",
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "The following snippets playsback the recorded trajectory of each particle.\n",
- "\n",
- "To get the insight of the motion model change the value of $R$ and re-run the cells again. As R is the parameters that indicates how much we trust that the robot executed the motion commands.\n",
- "\n",
- "It is interesting to notice also that only motion will increase the uncertainty in the system as the particles start to spread out more. If observations are included the uncertainty will decrease and particles will converge to the correct estimate."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [],
- "source": [
- "# CODE SNIPPET #\n",
- "import numpy as np\n",
- "import math\n",
- "from copy import deepcopy\n",
- "# Fast SLAM covariance\n",
- "Q = np.diag([3.0, np.deg2rad(10.0)])**2\n",
- "R = np.diag([1.0, np.deg2rad(20.0)])**2\n",
- "\n",
- "# Simulation parameter\n",
- "Qsim = np.diag([0.3, np.deg2rad(2.0)])**2\n",
- "Rsim = np.diag([0.5, np.deg2rad(10.0)])**2\n",
- "OFFSET_YAWRATE_NOISE = 0.01\n",
- "\n",
- "DT = 0.1 # time tick [s]\n",
- "SIM_TIME = 50.0 # simulation time [s]\n",
- "MAX_RANGE = 20.0 # maximum observation range\n",
- "M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.\n",
- "STATE_SIZE = 3 # State size [x,y,yaw]\n",
- "LM_SIZE = 2 # LM srate size [x,y]\n",
- "N_PARTICLE = 100 # number of particle\n",
- "NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling\n",
- "\n",
- "class Particle:\n",
- "\n",
- " def __init__(self, N_LM):\n",
- " self.w = 1.0 / N_PARTICLE\n",
- " self.x = 0.0\n",
- " self.y = 0.0\n",
- " self.yaw = 0.0\n",
- " # landmark x-y positions\n",
- " self.lm = np.zeros((N_LM, LM_SIZE))\n",
- " # landmark position covariance\n",
- " self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE))\n",
- "\n",
- "def motion_model(x, u):\n",
- " F = np.array([[1.0, 0, 0],\n",
- " [0, 1.0, 0],\n",
- " [0, 0, 1.0]])\n",
- "\n",
- " B = np.array([[DT * math.cos(x[2, 0]), 0],\n",
- " [DT * math.sin(x[2, 0]), 0],\n",
- " [0.0, DT]])\n",
- " x = F @ x + B @ u\n",
- " \n",
- " x[2, 0] = pi_2_pi(x[2, 0])\n",
- " return x\n",
- " \n",
- "def predict_particles(particles, u):\n",
- " for i in range(N_PARTICLE):\n",
- " px = np.zeros((STATE_SIZE, 1))\n",
- " px[0, 0] = particles[i].x\n",
- " px[1, 0] = particles[i].y\n",
- " px[2, 0] = particles[i].yaw\n",
- " ud = u + (np.random.randn(1, 2) @ R).T # add noise\n",
- " px = motion_model(px, ud)\n",
- " particles[i].x = px[0, 0]\n",
- " particles[i].y = px[1, 0]\n",
- " particles[i].yaw = px[2, 0]\n",
- "\n",
- " return particles\n",
- "\n",
- "def pi_2_pi(angle):\n",
- " return (angle + math.pi) % (2 * math.pi) - math.pi\n",
- "\n",
- "# END OF SNIPPET\n",
- "\n",
- "N_LM = 0 \n",
- "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n",
- "time= 0.0\n",
- "v = 1.0 # [m/s]\n",
- "yawrate = 0.1 # [rad/s]\n",
- "u = np.array([v, yawrate]).reshape(2, 1)\n",
- "history = []\n",
- "while SIM_TIME >= time:\n",
- " time += DT\n",
- " particles = predict_particles(particles, u)\n",
- " history.append(deepcopy(particles))\n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "application/vnd.jupyter.widget-view+json": {
- "model_id": "3f279cf1dcaf4ec886c01942c36e601d",
- "version_major": 2,
- "version_minor": 0
- },
- "text/plain": [
- "interactive(children=(IntSlider(value=0, description='t', max=499), Output()), _dom_classes=('widget-interact'…"
- ]
- },
- "metadata": {},
- "output_type": "display_data"
- }
- ],
- "source": [
- "# from IPython.html.widgets import *\n",
- "from ipywidgets import *\n",
- "import numpy as np\n",
- "import matplotlib.pyplot as plt\n",
- "%matplotlib inline\n",
- "\n",
- "# playback the recorded motion of the particles\n",
- "def plot_particles(t=0):\n",
- " x = []\n",
- " y = []\n",
- " for i in range(len(history[t])):\n",
- " x.append(history[t][i].x)\n",
- " y.append(history[t][i].y)\n",
- " plt.figtext(0.15,0.82,'t = ' + str(t))\n",
- " plt.plot(x, y, '.r')\n",
- " plt.axis([-20,20, -5,25])\n",
- "\n",
- "interact(plot_particles, t=(0,len(history)-1,1));"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### 2- Update\n",
- "\n",
- "For the update step it is useful to observe a single particle and the effect of getting a new measurements on the weight of the particle.\n",
- "\n",
- "As mentioned earlier, each particle maintains $N$ $2x2$ EKFs to estimate the landmarks, which includes the EKF process described in the EKF notebook. The difference is the change in the weight of the particle according to how likely the measurement is.\n",
- "\n",
- "The weight is updated according to the following equation: \n",
- "\n",
- "$\\begin{equation*}\n",
- "w_i = |2\\pi Q|^{\\frac{-1}{2}} exp\\{\\frac{-1}{2}(z_t - \\hat z_i)^T Q^{-1}(z_t-\\hat z_i)\\}\n",
- "\\end{equation*}$\n",
- "\n",
- "Where, $w_i$ is the computed weight, $Q$ is the measurement covariance, $z_t$ is the actual measurment and $\\hat z_i$ is the predicted measurement of particle $i$.\n",
- "\n",
- "To experiment this, a single particle is initialized then passed an initial measurement, which results in a relatively average weight. However, setting the particle coordinate to a wrong value to simulate wrong estimation will result in a very low weight. The lower the weight the less likely that this particle will be drawn during resampling and probably will die out."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 4,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "initial weight 1.0\n",
- "weight after landmark intialization 1.0\n",
- "weight after update 0.023098460073039763\n",
- "weight after wrong prediction 7.951154575772496e-07\n"
- ]
- }
- ],
- "source": [
- "# CODE SNIPPET #\n",
- "def observation(xTrue, xd, u, RFID):\n",
- "\n",
- " # calc true state\n",
- " xTrue = motion_model(xTrue, u)\n",
- "\n",
- " # add noise to range observation\n",
- " z = np.zeros((3, 0))\n",
- " for i in range(len(RFID[:, 0])):\n",
- "\n",
- " dx = RFID[i, 0] - xTrue[0, 0]\n",
- " dy = RFID[i, 1] - xTrue[1, 0]\n",
- " d = math.sqrt(dx**2 + dy**2)\n",
- " angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])\n",
- " if d <= MAX_RANGE:\n",
- " dn = d + np.random.randn() * Qsim[0, 0] # add noise\n",
- " anglen = angle + np.random.randn() * Qsim[1, 1] # add noise\n",
- " zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1)\n",
- " z = np.hstack((z, zi))\n",
- "\n",
- " # add noise to input\n",
- " ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]\n",
- " ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE\n",
- " ud = np.array([ud1, ud2]).reshape(2, 1)\n",
- "\n",
- " xd = motion_model(xd, ud)\n",
- "\n",
- " return xTrue, z, xd, ud\n",
- "\n",
- "def update_with_observation(particles, z):\n",
- " for iz in range(len(z[0, :])):\n",
- "\n",
- " lmid = int(z[2, iz])\n",
- "\n",
- " for ip in range(N_PARTICLE):\n",
- " # new landmark\n",
- " if abs(particles[ip].lm[lmid, 0]) <= 0.01:\n",
- " particles[ip] = add_new_lm(particles[ip], z[:, iz], Q)\n",
- " # known landmark\n",
- " else:\n",
- " w = compute_weight(particles[ip], z[:, iz], Q)\n",
- " particles[ip].w *= w\n",
- " particles[ip] = update_landmark(particles[ip], z[:, iz], Q)\n",
- "\n",
- " return particles\n",
- "\n",
- "def compute_weight(particle, z, Q):\n",
- " lm_id = int(z[2])\n",
- " xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)\n",
- " Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])\n",
- " zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)\n",
- " dx = z[0:2].reshape(2, 1) - zp\n",
- " dx[1, 0] = pi_2_pi(dx[1, 0])\n",
- "\n",
- " try:\n",
- " invS = np.linalg.inv(Sf)\n",
- " except np.linalg.linalg.LinAlgError:\n",
- " print(\"singuler\")\n",
- " return 1.0\n",
- "\n",
- " num = math.exp(-0.5 * dx.T @ invS @ dx)\n",
- " den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf))\n",
- " w = num / den\n",
- "\n",
- " return w\n",
- "\n",
- "def compute_jacobians(particle, xf, Pf, Q):\n",
- " dx = xf[0, 0] - particle.x\n",
- " dy = xf[1, 0] - particle.y\n",
- " d2 = dx**2 + dy**2\n",
- " d = math.sqrt(d2)\n",
- "\n",
- " zp = np.array(\n",
- " [d, pi_2_pi(math.atan2(dy, dx) - particle.yaw)]).reshape(2, 1)\n",
- "\n",
- " Hv = np.array([[-dx / d, -dy / d, 0.0],\n",
- " [dy / d2, -dx / d2, -1.0]])\n",
- "\n",
- " Hf = np.array([[dx / d, dy / d],\n",
- " [-dy / d2, dx / d2]])\n",
- "\n",
- " Sf = Hf @ Pf @ Hf.T + Q\n",
- "\n",
- " return zp, Hv, Hf, Sf\n",
- "\n",
- "def add_new_lm(particle, z, Q):\n",
- "\n",
- " r = z[0]\n",
- " b = z[1]\n",
- " lm_id = int(z[2])\n",
- "\n",
- " s = math.sin(pi_2_pi(particle.yaw + b))\n",
- " c = math.cos(pi_2_pi(particle.yaw + b))\n",
- "\n",
- " particle.lm[lm_id, 0] = particle.x + r * c\n",
- " particle.lm[lm_id, 1] = particle.y + r * s\n",
- "\n",
- " # covariance\n",
- " Gz = np.array([[c, -r * s],\n",
- " [s, r * c]])\n",
- "\n",
- " particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T\n",
- "\n",
- " return particle\n",
- "\n",
- "def update_KF_with_cholesky(xf, Pf, v, Q, Hf):\n",
- " PHt = Pf @ Hf.T\n",
- " S = Hf @ PHt + Q\n",
- "\n",
- " S = (S + S.T) * 0.5\n",
- " SChol = np.linalg.cholesky(S).T\n",
- " SCholInv = np.linalg.inv(SChol)\n",
- " W1 = PHt @ SCholInv\n",
- " W = W1 @ SCholInv.T\n",
- "\n",
- " x = xf + W @ v\n",
- " P = Pf - W1 @ W1.T\n",
- "\n",
- " return x, P\n",
- "\n",
- "def update_landmark(particle, z, Q):\n",
- "\n",
- " lm_id = int(z[2])\n",
- " xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)\n",
- " Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2, :])\n",
- "\n",
- " zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)\n",
- "\n",
- " dz = z[0:2].reshape(2, 1) - zp\n",
- " dz[1, 0] = pi_2_pi(dz[1, 0])\n",
- "\n",
- " xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf)\n",
- "\n",
- " particle.lm[lm_id, :] = xf.T\n",
- " particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf\n",
- "\n",
- " return particle\n",
- "\n",
- "# END OF CODE SNIPPET #\n",
- "\n",
- "\n",
- "\n",
- "# Setting up the landmarks\n",
- "RFID = np.array([[10.0, -2.0],\n",
- " [15.0, 10.0]])\n",
- "N_LM = RFID.shape[0]\n",
- "\n",
- "# Initialize 1 particle\n",
- "N_PARTICLE = 1\n",
- "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n",
- "\n",
- "xTrue = np.zeros((STATE_SIZE, 1))\n",
- "xDR = np.zeros((STATE_SIZE, 1))\n",
- "\n",
- "print(\"initial weight\", particles[0].w)\n",
- "\n",
- "xTrue, z, _, ud = observation(xTrue, xDR, u, RFID)\n",
- "# Initialize landmarks\n",
- "particles = update_with_observation(particles, z)\n",
- "print(\"weight after landmark intialization\", particles[0].w)\n",
- "particles = update_with_observation(particles, z)\n",
- "print(\"weight after update \", particles[0].w)\n",
- "\n",
- "particles[0].x = -10\n",
- "particles = update_with_observation(particles, z)\n",
- "print(\"weight after wrong prediction\", particles[0].w)\n",
- " "
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### 3- Resampling\n",
- "\n",
- "In the reseampling steps a new set of particles are chosen from the old set. This is done according to the weight of each particle. \n",
- "\n",
- "The figure shows 100 particles distributed uniformly between [-0.5, 0.5] with the weights of each particle distributed according to a Gaussian funciton. \n",
- "\n",
- "The resampling picks \n",
- "\n",
- "$i \\in 1,...,N$ particles with probability to pick particle with index $i ∝ \\omega_i$, where $\\omega_i$ is the weight of that particle\n",
- "\n",
- "\n",
- "To get the intuition of the resampling step we will look at a set of particles which are initialized with a given x location and weight. After the resampling the particles are more concetrated in the location where they had the highest weights. This is also indicated by the indices \n"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "# CODE SNIPPET #\n",
- "def normalize_weight(particles):\n",
- "\n",
- " sumw = sum([p.w for p in particles])\n",
- "\n",
- " try:\n",
- " for i in range(N_PARTICLE):\n",
- " particles[i].w /= sumw\n",
- " except ZeroDivisionError:\n",
- " for i in range(N_PARTICLE):\n",
- " particles[i].w = 1.0 / N_PARTICLE\n",
- "\n",
- " return particles\n",
- "\n",
- " return particles\n",
- "\n",
- "\n",
- "def resampling(particles):\n",
- " \"\"\"\n",
- " low variance re-sampling\n",
- " \"\"\"\n",
- "\n",
- " particles = normalize_weight(particles)\n",
- "\n",
- " pw = []\n",
- " for i in range(N_PARTICLE):\n",
- " pw.append(particles[i].w)\n",
- "\n",
- " pw = np.array(pw)\n",
- "\n",
- " Neff = 1.0 / (pw @ pw.T) # Effective particle number\n",
- " # print(Neff)\n",
- "\n",
- " if Neff < NTH: # resampling\n",
- " wcum = np.cumsum(pw)\n",
- " base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE\n",
- " resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE\n",
- "\n",
- " inds = []\n",
- " ind = 0\n",
- " for ip in range(N_PARTICLE):\n",
- " while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])):\n",
- " ind += 1\n",
- " inds.append(ind)\n",
- "\n",
- " tparticles = particles[:]\n",
- " for i in range(len(inds)):\n",
- " particles[i].x = tparticles[inds[i]].x\n",
- " particles[i].y = tparticles[inds[i]].y\n",
- " particles[i].yaw = tparticles[inds[i]].yaw\n",
- " particles[i].w = 1.0 / N_PARTICLE\n",
- "\n",
- " return particles, inds\n",
- "# END OF SNIPPET #\n",
- "\n",
- "\n",
- "\n",
- "def gaussian(x, mu, sig):\n",
- " return np.exp(-np.power(x - mu, 2.) / (2 * np.power(sig, 2.)))\n",
- "N_PARTICLE = 100\n",
- "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n",
- "x_pos = []\n",
- "w = []\n",
- "for i in range(N_PARTICLE):\n",
- " particles[i].x = np.linspace(-0.5,0.5,N_PARTICLE)[i]\n",
- " x_pos.append(particles[i].x)\n",
- " particles[i].w = gaussian(i, N_PARTICLE/2, N_PARTICLE/20)\n",
- " w.append(particles[i].w)\n",
- " \n",
- "\n",
- "# Normalize weights\n",
- "sw = sum(w)\n",
- "for i in range(N_PARTICLE):\n",
- " w[i] /= sw\n",
- "\n",
- "particles, new_indices = resampling(particles)\n",
- "x_pos2 = []\n",
- "for i in range(N_PARTICLE):\n",
- " x_pos2.append(particles[i].x)\n",
- " \n",
- "# Plot results\n",
- "fig, ((ax1,ax2,ax3)) = plt.subplots(nrows=3, ncols=1)\n",
- "fig.tight_layout()\n",
- "ax1.plot(x_pos,np.ones((N_PARTICLE,1)), '.r', markersize=2)\n",
- "ax1.set_title(\"Particles before resampling\")\n",
- "ax1.axis((-1, 1, 0, 2))\n",
- "ax2.plot(w)\n",
- "ax2.set_title(\"Weights distribution\")\n",
- "ax3.plot(x_pos2,np.ones((N_PARTICLE,1)), '.r')\n",
- "ax3.set_title(\"Particles after resampling\")\n",
- "ax3.axis((-1, 1, 0, 2))\n",
- "fig.subplots_adjust(hspace=0.8)\n",
- "plt.show()\n",
- "\n",
- "plt.figure()\n",
- "plt.hist(new_indices)\n",
- "plt.xlabel(\"Particles indices to be resampled\")\n",
- "plt.ylabel(\"# of time index is used\")\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### References\n",
- "\n",
- "http://www.probabilistic-robotics.org/\n",
- "\n",
- "http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.1"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/SLAM/FastSLAM1/animation.png b/SLAM/FastSLAM1/animation.png
deleted file mode 100644
index 86c2950f70..0000000000
Binary files a/SLAM/FastSLAM1/animation.png and /dev/null differ
diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py
index 757e9f95ad..98f8a66417 100644
--- a/SLAM/FastSLAM1/fast_slam1.py
+++ b/SLAM/FastSLAM1/fast_slam1.py
@@ -6,26 +6,27 @@
"""
-import numpy as np
import math
-import matplotlib.pyplot as plt
+import matplotlib.pyplot as plt
+import numpy as np
+from utils.angle import angle_mod
# Fast SLAM covariance
-Q = np.diag([3.0, np.deg2rad(10.0)])**2
-R = np.diag([1.0, np.deg2rad(20.0)])**2
+Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2
+R = np.diag([1.0, np.deg2rad(20.0)]) ** 2
# Simulation parameter
-Qsim = np.diag([0.3, np.deg2rad(2.0)])**2
-Rsim = np.diag([0.5, np.deg2rad(10.0)])**2
-OFFSET_YAWRATE_NOISE = 0.01
+Q_SIM = np.diag([0.3, np.deg2rad(2.0)]) ** 2
+R_SIM = np.diag([0.5, np.deg2rad(10.0)]) ** 2
+OFFSET_YAW_RATE_NOISE = 0.01
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
MAX_RANGE = 20.0 # maximum observation range
M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.
STATE_SIZE = 3 # State size [x,y,yaw]
-LM_SIZE = 2 # LM srate size [x,y]
+LM_SIZE = 2 # LM state size [x,y]
N_PARTICLE = 100 # number of particle
NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling
@@ -34,19 +35,18 @@
class Particle:
- def __init__(self, N_LM):
+ def __init__(self, n_landmark):
self.w = 1.0 / N_PARTICLE
self.x = 0.0
self.y = 0.0
self.yaw = 0.0
# landmark x-y positions
- self.lm = np.zeros((N_LM, LM_SIZE))
+ self.lm = np.zeros((n_landmark, LM_SIZE))
# landmark position covariance
- self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE))
+ self.lmP = np.zeros((n_landmark * LM_SIZE, LM_SIZE))
def fast_slam1(particles, u, z):
-
particles = predict_particles(particles, u)
particles = update_with_observation(particles, z)
@@ -57,12 +57,11 @@ def fast_slam1(particles, u, z):
def normalize_weight(particles):
-
- sumw = sum([p.w for p in particles])
+ sum_w = sum([p.w for p in particles])
try:
for i in range(N_PARTICLE):
- particles[i].w /= sumw
+ particles[i].w /= sum_w
except ZeroDivisionError:
for i in range(N_PARTICLE):
particles[i].w = 1.0 / N_PARTICLE
@@ -73,30 +72,27 @@ def normalize_weight(particles):
def calc_final_state(particles):
-
- xEst = np.zeros((STATE_SIZE, 1))
+ x_est = np.zeros((STATE_SIZE, 1))
particles = normalize_weight(particles)
for i in range(N_PARTICLE):
- xEst[0, 0] += particles[i].w * particles[i].x
- xEst[1, 0] += particles[i].w * particles[i].y
- xEst[2, 0] += particles[i].w * particles[i].yaw
+ x_est[0, 0] += particles[i].w * particles[i].x
+ x_est[1, 0] += particles[i].w * particles[i].y
+ x_est[2, 0] += particles[i].w * particles[i].yaw
- xEst[2, 0] = pi_2_pi(xEst[2, 0])
- # print(xEst)
+ x_est[2, 0] = pi_2_pi(x_est[2, 0])
- return xEst
+ return x_est
def predict_particles(particles, u):
-
for i in range(N_PARTICLE):
px = np.zeros((STATE_SIZE, 1))
px[0, 0] = particles[i].x
px[1, 0] = particles[i].y
px[2, 0] = particles[i].yaw
- ud = u + (np.random.randn(1, 2) @ R).T # add noise
+ ud = u + (np.random.randn(1, 2) @ R ** 0.5).T # add noise
px = motion_model(px, ud)
particles[i].x = px[0, 0]
particles[i].y = px[1, 0]
@@ -105,8 +101,7 @@ def predict_particles(particles, u):
return particles
-def add_new_lm(particle, z, Q):
-
+def add_new_landmark(particle, z, Q_cov):
r = z[0]
b = z[1]
lm_id = int(z[2])
@@ -118,18 +113,22 @@ def add_new_lm(particle, z, Q):
particle.lm[lm_id, 1] = particle.y + r * s
# covariance
- Gz = np.array([[c, -r * s],
- [s, r * c]])
-
- particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T
+ dx = r * c
+ dy = r * s
+ d2 = dx**2 + dy**2
+ d = math.sqrt(d2)
+ Gz = np.array([[dx / d, dy / d],
+ [-dy / d2, dx / d2]])
+ particle.lmP[2 * lm_id:2 * lm_id + 2] = np.linalg.inv(
+ Gz) @ Q_cov @ np.linalg.inv(Gz.T)
return particle
-def compute_jacobians(particle, xf, Pf, Q):
+def compute_jacobians(particle, xf, Pf, Q_cov):
dx = xf[0, 0] - particle.x
dy = xf[1, 0] - particle.y
- d2 = dx**2 + dy**2
+ d2 = dx ** 2 + dy ** 2
d = math.sqrt(d2)
zp = np.array(
@@ -141,20 +140,20 @@ def compute_jacobians(particle, xf, Pf, Q):
Hf = np.array([[dx / d, dy / d],
[-dy / d2, dx / d2]])
- Sf = Hf @ Pf @ Hf.T + Q
+ Sf = Hf @ Pf @ Hf.T + Q_cov
return zp, Hv, Hf, Sf
-def update_KF_with_cholesky(xf, Pf, v, Q, Hf):
+def update_kf_with_cholesky(xf, Pf, v, Q_cov, Hf):
PHt = Pf @ Hf.T
- S = Hf @ PHt + Q
+ S = Hf @ PHt + Q_cov
S = (S + S.T) * 0.5
- SChol = np.linalg.cholesky(S).T
- SCholInv = np.linalg.inv(SChol)
- W1 = PHt @ SCholInv
- W = W1 @ SCholInv.T
+ s_chol = np.linalg.cholesky(S).T
+ s_chol_inv = np.linalg.inv(s_chol)
+ W1 = PHt @ s_chol_inv
+ W = W1 @ s_chol_inv.T
x = xf + W @ v
P = Pf - W1 @ W1.T
@@ -162,8 +161,7 @@ def update_KF_with_cholesky(xf, Pf, v, Q, Hf):
return x, P
-def update_landmark(particle, z, Q):
-
+def update_landmark(particle, z, Q_cov):
lm_id = int(z[2])
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2, :])
@@ -173,7 +171,7 @@ def update_landmark(particle, z, Q):
dz = z[0:2].reshape(2, 1) - zp
dz[1, 0] = pi_2_pi(dz[1, 0])
- xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf)
+ xf, Pf = update_kf_with_cholesky(xf, Pf, dz, Q_cov, Hf)
particle.lm[lm_id, :] = xf.T
particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf
@@ -181,11 +179,11 @@ def update_landmark(particle, z, Q):
return particle
-def compute_weight(particle, z, Q):
+def compute_weight(particle, z, Q_cov):
lm_id = int(z[2])
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])
- zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
+ zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov)
dx = z[0:2].reshape(2, 1) - zp
dx[1, 0] = pi_2_pi(dx[1, 0])
@@ -193,10 +191,10 @@ def compute_weight(particle, z, Q):
try:
invS = np.linalg.inv(Sf)
except np.linalg.linalg.LinAlgError:
- print("singuler")
+ print("singular")
return 1.0
- num = math.exp(-0.5 * dx.T @ invS @ dx)
+ num = np.exp(-0.5 * (dx.T @ invS @ dx))[0, 0]
den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf))
w = num / den
@@ -205,15 +203,14 @@ def compute_weight(particle, z, Q):
def update_with_observation(particles, z):
-
for iz in range(len(z[0, :])):
- lmid = int(z[2, iz])
+ landmark_id = int(z[2, iz])
for ip in range(N_PARTICLE):
# new landmark
- if abs(particles[ip].lm[lmid, 0]) <= 0.01:
- particles[ip] = add_new_lm(particles[ip], z[:, iz], Q)
+ if abs(particles[ip].lm[landmark_id, 0]) <= 0.01:
+ particles[ip] = add_new_landmark(particles[ip], z[:, iz], Q)
# known landmark
else:
w = compute_weight(particles[ip], z[:, iz], Q)
@@ -236,78 +233,77 @@ def resampling(particles):
pw = np.array(pw)
- Neff = 1.0 / (pw @ pw.T) # Effective particle number
- # print(Neff)
+ n_eff = 1.0 / (pw @ pw.T) # Effective particle number
- if Neff < NTH: # resampling
- wcum = np.cumsum(pw)
+ if n_eff < NTH: # resampling
+ w_cum = np.cumsum(pw)
base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE
- resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE
+ resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE
- inds = []
- ind = 0
+ indexes = []
+ index = 0
for ip in range(N_PARTICLE):
- while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])):
- ind += 1
- inds.append(ind)
-
- tparticles = particles[:]
- for i in range(len(inds)):
- particles[i].x = tparticles[inds[i]].x
- particles[i].y = tparticles[inds[i]].y
- particles[i].yaw = tparticles[inds[i]].yaw
- particles[i].lm = tparticles[inds[i]].lm[:, :]
- particles[i].lmP = tparticles[inds[i]].lmP[:, :]
+ while (index < w_cum.shape[0] - 1) \
+ and (resample_id[ip] > w_cum[index]):
+ index += 1
+ indexes.append(index)
+
+ tmp_particles = particles[:]
+ for i in range(len(indexes)):
+ particles[i].x = tmp_particles[indexes[i]].x
+ particles[i].y = tmp_particles[indexes[i]].y
+ particles[i].yaw = tmp_particles[indexes[i]].yaw
+ particles[i].lm = tmp_particles[indexes[i]].lm[:, :]
+ particles[i].lmP = tmp_particles[indexes[i]].lmP[:, :]
particles[i].w = 1.0 / N_PARTICLE
return particles
def calc_input(time):
-
if time <= 3.0: # wait at first
v = 0.0
- yawrate = 0.0
+ yaw_rate = 0.0
else:
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
+ yaw_rate = 0.1 # [rad/s]
- u = np.array([v, yawrate]).reshape(2, 1)
+ u = np.array([v, yaw_rate]).reshape(2, 1)
return u
-def observation(xTrue, xd, u, RFID):
-
+def observation(x_true, xd, u, rfid):
# calc true state
- xTrue = motion_model(xTrue, u)
+ x_true = motion_model(x_true, u)
# add noise to range observation
z = np.zeros((3, 0))
- for i in range(len(RFID[:, 0])):
+ for i in range(len(rfid[:, 0])):
- dx = RFID[i, 0] - xTrue[0, 0]
- dy = RFID[i, 1] - xTrue[1, 0]
- d = math.sqrt(dx**2 + dy**2)
- angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
+ dx = rfid[i, 0] - x_true[0, 0]
+ dy = rfid[i, 1] - x_true[1, 0]
+ d = math.hypot(dx, dy)
+ angle = pi_2_pi(math.atan2(dy, dx) - x_true[2, 0])
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
- zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1)
+ dn = d + np.random.randn() * Q_SIM[0, 0] ** 0.5 # add noise
+ angle_with_noize = angle + np.random.randn() * Q_SIM[
+ 1, 1] ** 0.5 # add noise
+ zi = np.array([dn, pi_2_pi(angle_with_noize), i]).reshape(3, 1)
z = np.hstack((z, zi))
# add noise to input
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE
+ ud1 = u[0, 0] + np.random.randn() * R_SIM[0, 0] ** 0.5
+ ud2 = u[1, 0] + np.random.randn() * R_SIM[
+ 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE
ud = np.array([ud1, ud2]).reshape(2, 1)
xd = motion_model(xd, ud)
- return xTrue, z, xd, ud
+ return x_true, z, xd, ud
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0],
[0, 1.0, 0],
[0, 0, 1.0]])
@@ -324,7 +320,7 @@ def motion_model(x, u):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def main():
@@ -333,7 +329,7 @@ def main():
time = 0.0
# RFID positions [x, y]
- RFID = np.array([[10.0, -2.0],
+ rfid = np.array([[10.0, -2.0],
[15.0, 10.0],
[15.0, 15.0],
[10.0, 20.0],
@@ -342,49 +338,53 @@ def main():
[-5.0, 5.0],
[-10.0, 15.0]
])
- N_LM = RFID.shape[0]
+ n_landmark = rfid.shape[0]
# State Vector [x y yaw v]'
- xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation
- xTrue = np.zeros((STATE_SIZE, 1)) # True state
- xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning
+ x_est = np.zeros((STATE_SIZE, 1)) # SLAM estimation
+ x_true = np.zeros((STATE_SIZE, 1)) # True state
+ x_dr = np.zeros((STATE_SIZE, 1)) # Dead reckoning
# history
- hxEst = xEst
- hxTrue = xTrue
- hxDR = xTrue
+ hist_x_est = x_est
+ hist_x_true = x_true
+ hist_x_dr = x_dr
- particles = [Particle(N_LM) for i in range(N_PARTICLE)]
+ particles = [Particle(n_landmark) for _ in range(N_PARTICLE)]
while SIM_TIME >= time:
time += DT
u = calc_input(time)
- xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+ x_true, z, x_dr, ud = observation(x_true, x_dr, u, rfid)
particles = fast_slam1(particles, ud, z)
- xEst = calc_final_state(particles)
+ x_est = calc_final_state(particles)
- x_state = xEst[0: STATE_SIZE]
+ x_state = x_est[0: STATE_SIZE]
# store data history
- hxEst = np.hstack((hxEst, x_state))
- hxDR = np.hstack((hxDR, xDR))
- hxTrue = np.hstack((hxTrue, xTrue))
+ hist_x_est = np.hstack((hist_x_est, x_state))
+ hist_x_dr = np.hstack((hist_x_dr, x_dr))
+ hist_x_true = np.hstack((hist_x_true, x_true))
if show_animation: # pragma: no cover
plt.cla()
- plt.plot(RFID[:, 0], RFID[:, 1], "*k")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event', lambda event:
+ [exit(0) if event.key == 'escape' else None])
+ plt.plot(rfid[:, 0], rfid[:, 1], "*k")
for i in range(N_PARTICLE):
plt.plot(particles[i].x, particles[i].y, ".r")
plt.plot(particles[i].lm[:, 0], particles[i].lm[:, 1], "xb")
- plt.plot(hxTrue[0, :], hxTrue[1, :], "-b")
- plt.plot(hxDR[0, :], hxDR[1, :], "-k")
- plt.plot(hxEst[0, :], hxEst[1, :], "-r")
- plt.plot(xEst[0], xEst[1], "xk")
+ plt.plot(hist_x_true[0, :], hist_x_true[1, :], "-b")
+ plt.plot(hist_x_dr[0, :], hist_x_dr[1, :], "-k")
+ plt.plot(hist_x_est[0, :], hist_x_est[1, :], "-r")
+ plt.plot(x_est[0], x_est[1], "xk")
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py
index 3d73a58e30..d4cf0d84dd 100644
--- a/SLAM/FastSLAM2/fast_slam2.py
+++ b/SLAM/FastSLAM2/fast_slam2.py
@@ -6,26 +6,27 @@
"""
-import numpy as np
import math
-import matplotlib.pyplot as plt
+import matplotlib.pyplot as plt
+import numpy as np
+from utils.angle import angle_mod
# Fast SLAM covariance
-Q = np.diag([3.0, np.deg2rad(10.0)])**2
-R = np.diag([1.0, np.deg2rad(20.0)])**2
+Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2
+R = np.diag([1.0, np.deg2rad(20.0)]) ** 2
# Simulation parameter
-Qsim = np.diag([0.3, np.deg2rad(2.0)])**2
-Rsim = np.diag([0.5, np.deg2rad(10.0)])**2
-OFFSET_YAWRATE_NOISE = 0.01
+Q_SIM = np.diag([0.3, np.deg2rad(2.0)]) ** 2
+R_SIM = np.diag([0.5, np.deg2rad(10.0)]) ** 2
+OFFSET_YAW_RATE_NOISE = 0.01
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
MAX_RANGE = 20.0 # maximum observation range
M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.
STATE_SIZE = 3 # State size [x,y,yaw]
-LM_SIZE = 2 # LM srate size [x,y]
+LM_SIZE = 2 # LM state size [x,y]
N_PARTICLE = 100 # number of particle
NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling
@@ -34,20 +35,19 @@
class Particle:
- def __init__(self, N_LM):
+ def __init__(self, n_landmark):
self.w = 1.0 / N_PARTICLE
self.x = 0.0
self.y = 0.0
self.yaw = 0.0
self.P = np.eye(3)
# landmark x-y positions
- self.lm = np.zeros((N_LM, LM_SIZE))
+ self.lm = np.zeros((n_landmark, LM_SIZE))
# landmark position covariance
- self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE))
+ self.lmP = np.zeros((n_landmark * LM_SIZE, LM_SIZE))
def fast_slam2(particles, u, z):
-
particles = predict_particles(particles, u)
particles = update_with_observation(particles, z)
@@ -58,12 +58,11 @@ def fast_slam2(particles, u, z):
def normalize_weight(particles):
-
- sumw = sum([p.w for p in particles])
+ sum_w = sum([p.w for p in particles])
try:
for i in range(N_PARTICLE):
- particles[i].w /= sumw
+ particles[i].w /= sum_w
except ZeroDivisionError:
for i in range(N_PARTICLE):
particles[i].w = 1.0 / N_PARTICLE
@@ -74,30 +73,27 @@ def normalize_weight(particles):
def calc_final_state(particles):
-
- xEst = np.zeros((STATE_SIZE, 1))
+ x_est = np.zeros((STATE_SIZE, 1))
particles = normalize_weight(particles)
for i in range(N_PARTICLE):
- xEst[0, 0] += particles[i].w * particles[i].x
- xEst[1, 0] += particles[i].w * particles[i].y
- xEst[2, 0] += particles[i].w * particles[i].yaw
+ x_est[0, 0] += particles[i].w * particles[i].x
+ x_est[1, 0] += particles[i].w * particles[i].y
+ x_est[2, 0] += particles[i].w * particles[i].yaw
- xEst[2, 0] = pi_2_pi(xEst[2, 0])
- # print(xEst)
+ x_est[2, 0] = pi_2_pi(x_est[2, 0])
- return xEst
+ return x_est
def predict_particles(particles, u):
-
for i in range(N_PARTICLE):
px = np.zeros((STATE_SIZE, 1))
px[0, 0] = particles[i].x
px[1, 0] = particles[i].y
px[2, 0] = particles[i].yaw
- ud = u + (np.random.randn(1, 2) @ R).T # add noise
+ ud = u + (np.random.randn(1, 2) @ R ** 0.5).T # add noise
px = motion_model(px, ud)
particles[i].x = px[0, 0]
particles[i].y = px[1, 0]
@@ -106,8 +102,7 @@ def predict_particles(particles, u):
return particles
-def add_new_lm(particle, z, Q):
-
+def add_new_lm(particle, z, Q_cov):
r = z[0]
b = z[1]
lm_id = int(z[2])
@@ -119,18 +114,22 @@ def add_new_lm(particle, z, Q):
particle.lm[lm_id, 1] = particle.y + r * s
# covariance
- Gz = np.array([[c, -r * s],
- [s, r * c]])
-
- particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T
+ dx = r * c
+ dy = r * s
+ d2 = dx ** 2 + dy ** 2
+ d = math.sqrt(d2)
+ Gz = np.array([[dx / d, dy / d],
+ [-dy / d2, dx / d2]])
+ particle.lmP[2 * lm_id:2 * lm_id + 2] = np.linalg.inv(
+ Gz) @ Q_cov @ np.linalg.inv(Gz.T)
return particle
-def compute_jacobians(particle, xf, Pf, Q):
+def compute_jacobians(particle, xf, Pf, Q_cov):
dx = xf[0, 0] - particle.x
dy = xf[1, 0] - particle.y
- d2 = dx**2 + dy**2
+ d2 = dx ** 2 + dy ** 2
d = math.sqrt(d2)
zp = np.array(
@@ -142,14 +141,14 @@ def compute_jacobians(particle, xf, Pf, Q):
Hf = np.array([[dx / d, dy / d],
[-dy / d2, dx / d2]])
- Sf = Hf @ Pf @ Hf.T + Q
+ Sf = Hf @ Pf @ Hf.T + Q_cov
return zp, Hv, Hf, Sf
-def update_KF_with_cholesky(xf, Pf, v, Q, Hf):
+def update_kf_with_cholesky(xf, Pf, v, Q_cov, Hf):
PHt = Pf @ Hf.T
- S = Hf @ PHt + Q
+ S = Hf @ PHt + Q_cov
S = (S + S.T) * 0.5
SChol = np.linalg.cholesky(S).T
@@ -163,18 +162,17 @@ def update_KF_with_cholesky(xf, Pf, v, Q, Hf):
return x, P
-def update_landmark(particle, z, Q):
-
+def update_landmark(particle, z, Q_cov):
lm_id = int(z[2])
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])
- zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
+ zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov)
dz = z[0:2].reshape(2, 1) - zp
dz[1, 0] = pi_2_pi(dz[1, 0])
- xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf)
+ xf, Pf = update_kf_with_cholesky(xf, Pf, dz, Q, Hf)
particle.lm[lm_id, :] = xf.T
particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf
@@ -182,12 +180,11 @@ def update_landmark(particle, z, Q):
return particle
-def compute_weight(particle, z, Q):
-
+def compute_weight(particle, z, Q_cov):
lm_id = int(z[2])
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])
- zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
+ zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov)
dz = z[0:2].reshape(2, 1) - zp
dz[1, 0] = pi_2_pi(dz[1, 0])
@@ -197,7 +194,7 @@ def compute_weight(particle, z, Q):
except np.linalg.linalg.LinAlgError:
return 1.0
- num = math.exp(-0.5 * dz.T @ invS @ dz)
+ num = np.exp(-0.5 * dz.T @ invS @ dz)[0, 0]
den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf))
w = num / den
@@ -205,15 +202,14 @@ def compute_weight(particle, z, Q):
return w
-def proposal_sampling(particle, z, Q):
-
+def proposal_sampling(particle, z, Q_cov):
lm_id = int(z[2])
xf = particle.lm[lm_id, :].reshape(2, 1)
Pf = particle.lmP[2 * lm_id:2 * lm_id + 2]
# State
x = np.array([particle.x, particle.y, particle.yaw]).reshape(3, 1)
P = particle.P
- zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
+ zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov)
Sfi = np.linalg.inv(Sf)
dz = z[0:2].reshape(2, 1) - zp
@@ -232,13 +228,12 @@ def proposal_sampling(particle, z, Q):
def update_with_observation(particles, z):
-
for iz in range(len(z[0, :])):
- lmid = int(z[2, iz])
+ landmark_id = int(z[2, iz])
for ip in range(N_PARTICLE):
# new landmark
- if abs(particles[ip].lm[lmid, 0]) <= 0.01:
+ if abs(particles[ip].lm[landmark_id, 0]) <= 0.01:
particles[ip] = add_new_lm(particles[ip], z[:, iz], Q)
# known landmark
else:
@@ -264,79 +259,78 @@ def resampling(particles):
pw = np.array(pw)
- Neff = 1.0 / (pw @ pw.T) # Effective particle number
- # print(Neff)
+ n_eff = 1.0 / (pw @ pw.T) # Effective particle number
- if Neff < NTH: # resampling
- wcum = np.cumsum(pw)
+ if n_eff < NTH: # resampling
+ w_cum = np.cumsum(pw)
base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE
- resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE
+ resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE
- inds = []
- ind = 0
+ indexes = []
+ index = 0
for ip in range(N_PARTICLE):
- while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])):
- ind += 1
- inds.append(ind)
-
- tparticles = particles[:]
- for i in range(len(inds)):
- particles[i].x = tparticles[inds[i]].x
- particles[i].y = tparticles[inds[i]].y
- particles[i].yaw = tparticles[inds[i]].yaw
- particles[i].lm = tparticles[inds[i]].lm[:, :]
- particles[i].lmP = tparticles[inds[i]].lmP[:, :]
+ while (index < w_cum.shape[0] - 1) \
+ and (resample_id[ip] > w_cum[index]):
+ index += 1
+ indexes.append(index)
+
+ tmp_particles = particles[:]
+ for i in range(len(indexes)):
+ particles[i].x = tmp_particles[indexes[i]].x
+ particles[i].y = tmp_particles[indexes[i]].y
+ particles[i].yaw = tmp_particles[indexes[i]].yaw
+ particles[i].lm = tmp_particles[indexes[i]].lm[:, :]
+ particles[i].lmP = tmp_particles[indexes[i]].lmP[:, :]
particles[i].w = 1.0 / N_PARTICLE
return particles
def calc_input(time):
-
if time <= 3.0: # wait at first
v = 0.0
- yawrate = 0.0
+ yaw_rate = 0.0
else:
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
+ yaw_rate = 0.1 # [rad/s]
- u = np.array([v, yawrate]).reshape(2, 1)
+ u = np.array([v, yaw_rate]).reshape(2, 1)
return u
-def observation(xTrue, xd, u, RFID):
-
+def observation(x_true, xd, u, rfid):
# calc true state
- xTrue = motion_model(xTrue, u)
+ x_true = motion_model(x_true, u)
# add noise to range observation
z = np.zeros((3, 0))
- for i in range(len(RFID[:, 0])):
+ for i in range(len(rfid[:, 0])):
- dx = RFID[i, 0] - xTrue[0, 0]
- dy = RFID[i, 1] - xTrue[1, 0]
- d = math.sqrt(dx**2 + dy**2)
- angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
+ dx = rfid[i, 0] - x_true[0, 0]
+ dy = rfid[i, 1] - x_true[1, 0]
+ d = math.hypot(dx, dy)
+ angle = pi_2_pi(math.atan2(dy, dx) - x_true[2, 0])
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
- zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1)
+ dn = d + np.random.randn() * Q_SIM[0, 0] ** 0.5 # add noise
+ angle_noise = np.random.randn() * Q_SIM[1, 1] ** 0.5
+ angle_with_noise = angle + angle_noise # add noise
+ zi = np.array([dn, pi_2_pi(angle_with_noise), i]).reshape(3, 1)
z = np.hstack((z, zi))
# add noise to input
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE
+ ud1 = u[0, 0] + np.random.randn() * R_SIM[0, 0] ** 0.5
+ ud2 = u[1, 0] + np.random.randn() * R_SIM[
+ 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE
ud = np.array([ud1, ud2]).reshape(2, 1)
xd = motion_model(xd, ud)
- return xTrue, z, xd, ud
+ return x_true, z, xd, ud
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0],
[0, 1.0, 0],
[0, 0, 1.0]])
@@ -353,7 +347,7 @@ def motion_model(x, u):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def main():
@@ -362,7 +356,7 @@ def main():
time = 0.0
# RFID positions [x, y]
- RFID = np.array([[10.0, -2.0],
+ rfid = np.array([[10.0, -2.0],
[15.0, 10.0],
[15.0, 15.0],
[10.0, 20.0],
@@ -371,54 +365,58 @@ def main():
[-5.0, 5.0],
[-10.0, 15.0]
])
- N_LM = RFID.shape[0]
+ n_landmark = rfid.shape[0]
# State Vector [x y yaw v]'
- xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation
- xTrue = np.zeros((STATE_SIZE, 1)) # True state
- xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning
+ x_est = np.zeros((STATE_SIZE, 1)) # SLAM estimation
+ x_true = np.zeros((STATE_SIZE, 1)) # True state
+ x_dr = np.zeros((STATE_SIZE, 1)) # Dead reckoning
# history
- hxEst = xEst
- hxTrue = xTrue
- hxDR = xTrue
+ hist_x_est = x_est
+ hist_x_true = x_true
+ hist_x_dr = x_dr
- particles = [Particle(N_LM) for i in range(N_PARTICLE)]
+ particles = [Particle(n_landmark) for _ in range(N_PARTICLE)]
while SIM_TIME >= time:
time += DT
u = calc_input(time)
- xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+ x_true, z, x_dr, ud = observation(x_true, x_dr, u, rfid)
particles = fast_slam2(particles, ud, z)
- xEst = calc_final_state(particles)
+ x_est = calc_final_state(particles)
- x_state = xEst[0: STATE_SIZE]
+ x_state = x_est[0: STATE_SIZE]
# store data history
- hxEst = np.hstack((hxEst, x_state))
- hxDR = np.hstack((hxDR, xDR))
- hxTrue = np.hstack((hxTrue, xTrue))
+ hist_x_est = np.hstack((hist_x_est, x_state))
+ hist_x_dr = np.hstack((hist_x_dr, x_dr))
+ hist_x_true = np.hstack((hist_x_true, x_true))
if show_animation: # pragma: no cover
plt.cla()
- plt.plot(RFID[:, 0], RFID[:, 1], "*k")
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ plt.plot(rfid[:, 0], rfid[:, 1], "*k")
for iz in range(len(z[:, 0])):
- lmid = int(z[2, iz])
- plt.plot([xEst[0], RFID[lmid, 0]], [
- xEst[1], RFID[lmid, 1]], "-k")
+ landmark_id = int(z[2, iz])
+ plt.plot([x_est[0][0], rfid[landmark_id, 0]], [
+ x_est[1][0], rfid[landmark_id, 1]], "-k")
for i in range(N_PARTICLE):
plt.plot(particles[i].x, particles[i].y, ".r")
plt.plot(particles[i].lm[:, 0], particles[i].lm[:, 1], "xb")
- plt.plot(hxTrue[0, :], hxTrue[1, :], "-b")
- plt.plot(hxDR[0, :], hxDR[1, :], "-k")
- plt.plot(hxEst[0, :], hxEst[1, :], "-r")
- plt.plot(xEst[0], xEst[1], "xk")
+ plt.plot(hist_x_true[0, :], hist_x_true[1, :], "-b")
+ plt.plot(hist_x_dr[0, :], hist_x_dr[1, :], "-k")
+ plt.plot(hist_x_est[0, :], hist_x_est[1, :], "-r")
+ plt.plot(x_est[0], x_est[1], "xk")
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
diff --git a/SLAM/GraphBasedSLAM/data/README.rst b/SLAM/GraphBasedSLAM/data/README.rst
new file mode 100644
index 0000000000..15bc5b6c03
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/data/README.rst
@@ -0,0 +1,6 @@
+Acknowledgments and References
+==============================
+
+Thanks to Luca Larlone for allowing inclusion of the `Intel dataset `_ in this repo.
+
+1. Carlone, L. and Censi, A., 2014. `From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimization `_. IEEE Transactions on Robotics, 30(2), pp.475-492.
diff --git a/SLAM/GraphBasedSLAM/data/input_INTEL.g2o b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o
new file mode 100644
index 0000000000..16f3a2600c
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o
@@ -0,0 +1,2711 @@
+VERTEX_SE2 0 0.000000 0.000000 0.000000
+VERTEX_SE2 1 0.000000 0.000000 -0.000642
+VERTEX_SE2 2 0.000000 0.000000 -0.001180
+VERTEX_SE2 3 0.011002 -0.000975 -0.003562
+VERTEX_SE2 4 0.641008 -0.011200 -0.007444
+VERTEX_SE2 5 0.696016 -0.011716 -0.098726
+VERTEX_SE2 6 0.700269 -0.015435 -0.895998
+VERTEX_SE2 7 0.693956 0.004213 -1.511535
+VERTEX_SE2 8 0.699263 0.026693 -2.125069
+VERTEX_SE2 9 0.716114 0.041122 -2.763139
+VERTEX_SE2 10 0.728981 0.043219 2.905515
+VERTEX_SE2 11 0.733203 0.040537 2.231236
+VERTEX_SE2 12 0.733186 0.041545 1.581762
+VERTEX_SE2 13 0.738753 0.059070 0.922264
+VERTEX_SE2 14 0.759658 0.073750 0.314025
+VERTEX_SE2 15 0.768572 0.074357 -0.210903
+VERTEX_SE2 16 1.062493 0.014152 -0.229595
+VERTEX_SE2 17 1.663647 -0.133115 -0.260823
+VERTEX_SE2 18 2.287001 -0.296480 -0.271000
+VERTEX_SE2 19 2.914298 -0.494254 -0.319576
+VERTEX_SE2 20 3.527220 -0.693985 -0.308933
+VERTEX_SE2 21 4.152895 -0.850915 -0.191238
+VERTEX_SE2 22 4.779015 -0.992339 -0.168556
+VERTEX_SE2 23 5.423978 -1.030005 -0.054484
+VERTEX_SE2 24 6.064382 -1.090997 -0.105423
+VERTEX_SE2 25 6.707928 -1.144401 -0.096821
+VERTEX_SE2 26 7.315680 -1.224079 -0.137153
+VERTEX_SE2 27 7.929761 -1.294250 -0.121079
+VERTEX_SE2 28 8.510243 -1.372635 -0.125240
+VERTEX_SE2 29 8.886549 -1.416447 -0.094136
+VERTEX_SE2 30 8.893462 -1.418023 -0.625522
+VERTEX_SE2 31 9.005697 -1.557779 -0.893355
+VERTEX_SE2 32 9.398300 -2.067296 -0.911506
+VERTEX_SE2 33 9.800909 -2.566880 -0.858368
+VERTEX_SE2 34 10.230894 -3.045076 -0.834898
+VERTEX_SE2 35 10.670845 -3.512974 -0.797906
+VERTEX_SE2 36 11.118351 -3.980273 -0.803680
+VERTEX_SE2 37 11.413882 -4.282108 -0.793023
+VERTEX_SE2 38 11.416535 -4.285316 -1.109584
+VERTEX_SE2 39 11.425445 -4.316267 -1.276487
+VERTEX_SE2 40 11.612551 -4.916547 -1.255922
+VERTEX_SE2 41 11.808527 -5.541274 -1.284316
+VERTEX_SE2 42 11.976726 -6.133098 -1.303279
+VERTEX_SE2 43 12.132495 -6.760248 -1.339357
+VERTEX_SE2 44 12.273339 -7.389611 -1.372003
+VERTEX_SE2 45 12.381155 -8.023418 -1.427426
+VERTEX_SE2 46 12.464524 -8.661631 -1.446702
+VERTEX_SE2 47 12.536773 -9.300726 -1.488240
+VERTEX_SE2 48 12.585187 -9.946461 -1.494639
+VERTEX_SE2 49 12.629508 -10.588502 -1.545288
+VERTEX_SE2 50 12.623735 -11.202499 -1.589586
+VERTEX_SE2 51 12.613473 -11.816834 -1.619614
+VERTEX_SE2 52 12.558110 -12.427134 -1.697131
+VERTEX_SE2 53 12.497320 -13.013155 -1.685264
+VERTEX_SE2 54 12.418711 -13.557683 -1.747661
+VERTEX_SE2 55 12.419724 -13.549747 -1.742676
+VERTEX_SE2 56 12.414345 -13.580353 -1.732396
+VERTEX_SE2 57 12.310914 -14.233877 -1.743844
+VERTEX_SE2 58 12.203756 -14.876538 -1.697418
+VERTEX_SE2 59 12.115088 -15.515348 -1.720561
+VERTEX_SE2 60 12.025760 -16.150800 -1.698500
+VERTEX_SE2 61 11.930749 -16.787980 -1.748266
+VERTEX_SE2 62 11.833006 -17.390733 -1.709239
+VERTEX_SE2 63 11.733602 -17.998517 -1.746382
+VERTEX_SE2 64 11.649132 -18.607583 -1.685617
+VERTEX_SE2 65 11.563367 -19.214882 -1.740522
+VERTEX_SE2 66 11.460058 -19.848621 -1.752656
+VERTEX_SE2 67 11.343148 -20.481952 -1.756181
+VERTEX_SE2 68 11.257571 -20.955257 -1.774331
+VERTEX_SE2 69 11.255185 -20.964979 -1.932353
+VERTEX_SE2 70 11.251937 -20.972069 -2.613265
+VERTEX_SE2 71 11.258227 -20.971402 3.020985
+VERTEX_SE2 72 11.258227 -20.971402 3.009195
+VERTEX_SE2 73 11.254702 -20.970679 2.941681
+VERTEX_SE2 74 11.251643 -20.968771 2.313797
+VERTEX_SE2 75 11.250298 -20.968291 1.957266
+VERTEX_SE2 76 11.239515 -20.956998 2.644600
+VERTEX_SE2 77 11.227570 -20.952338 2.874132
+VERTEX_SE2 78 10.929861 -20.969392 -3.076000
+VERTEX_SE2 79 10.295660 -21.019100 -3.083625
+VERTEX_SE2 80 9.648073 -21.026221 3.122276
+VERTEX_SE2 81 9.008652 -21.005804 3.093707
+VERTEX_SE2 82 8.367330 -20.952196 3.043418
+VERTEX_SE2 83 7.730227 -20.888698 3.024388
+VERTEX_SE2 84 7.095779 -20.785072 2.952781
+VERTEX_SE2 85 6.465179 -20.660326 2.966718
+VERTEX_SE2 86 5.750805 -20.513125 2.886729
+VERTEX_SE2 87 5.163554 -20.341011 2.848617
+VERTEX_SE2 88 4.815868 -20.234565 2.823505
+VERTEX_SE2 89 4.792324 -20.235107 -3.054605
+VERTEX_SE2 90 4.149209 -20.288628 -3.081395
+VERTEX_SE2 91 3.497178 -20.337577 -3.028289
+VERTEX_SE2 92 2.861629 -20.387679 -3.140035
+VERTEX_SE2 93 2.221011 -20.339858 3.045531
+VERTEX_SE2 94 1.585959 -20.258625 3.005168
+VERTEX_SE2 95 0.940663 -20.228767 -3.139936
+VERTEX_SE2 96 0.302216 -20.232542 -3.119921
+VERTEX_SE2 97 -0.314018 -20.219530 3.087656
+VERTEX_SE2 98 -0.922581 -20.164719 3.024330
+VERTEX_SE2 99 -1.648795 -20.093526 3.065410
+VERTEX_SE2 100 -2.230833 -20.023281 3.007277
+VERTEX_SE2 101 -2.871354 -20.005103 3.102942
+VERTEX_SE2 102 -3.516483 -19.955697 3.008603
+VERTEX_SE2 103 -4.152223 -19.878149 3.115724
+VERTEX_SE2 104 -4.795838 -19.847155 3.090758
+VERTEX_SE2 105 -5.440965 -19.834033 -3.137000
+VERTEX_SE2 106 -6.074366 -19.819256 3.099547
+VERTEX_SE2 107 -6.721384 -19.784913 3.102775
+VERTEX_SE2 108 -7.140409 -19.781530 -3.121388
+VERTEX_SE2 109 -7.153321 -19.779550 2.708464
+VERTEX_SE2 110 -7.164494 -19.769929 2.111343
+VERTEX_SE2 111 -7.174123 -19.662635 1.600354
+VERTEX_SE2 112 -7.201482 -19.000514 1.652438
+VERTEX_SE2 113 -7.269988 -18.356059 1.697296
+VERTEX_SE2 114 -7.351668 -17.722124 1.732079
+VERTEX_SE2 115 -7.477063 -17.090635 1.787906
+VERTEX_SE2 116 -7.655600 -16.348269 1.827325
+VERTEX_SE2 117 -7.838440 -15.740356 1.917383
+VERTEX_SE2 118 -7.847180 -15.710500 1.574139
+VERTEX_SE2 119 -7.822729 -15.211952 1.515457
+VERTEX_SE2 120 -7.806541 -14.573234 1.599604
+VERTEX_SE2 121 -7.846755 -13.965257 1.661084
+VERTEX_SE2 122 -7.908309 -13.357352 1.710992
+VERTEX_SE2 123 -7.944931 -13.145472 1.692222
+VERTEX_SE2 124 -7.867047 -12.909702 1.255856
+VERTEX_SE2 125 -7.662551 -12.318719 1.238631
+VERTEX_SE2 126 -7.536130 -11.694942 1.435606
+VERTEX_SE2 127 -7.446823 -11.065323 1.432524
+VERTEX_SE2 128 -7.378220 -10.424022 1.466677
+VERTEX_SE2 129 -7.297629 -9.790420 1.431058
+VERTEX_SE2 130 -7.233612 -9.152396 1.479951
+VERTEX_SE2 131 -7.188908 -8.512333 1.563552
+VERTEX_SE2 132 -7.169731 -7.871150 1.508512
+VERTEX_SE2 133 -7.117635 -7.291335 1.466418
+VERTEX_SE2 134 -7.055851 -6.684237 1.442294
+VERTEX_SE2 135 -6.963757 -6.111663 1.409225
+VERTEX_SE2 136 -6.874804 -5.474955 1.421265
+VERTEX_SE2 137 -6.760504 -4.850881 1.369865
+VERTEX_SE2 138 -6.660597 -4.217332 1.438397
+VERTEX_SE2 139 -6.600415 -3.595492 1.503413
+VERTEX_SE2 140 -6.582744 -2.945853 1.533669
+VERTEX_SE2 141 -6.543894 -2.313106 1.484948
+VERTEX_SE2 142 -6.498552 -1.671107 1.480848
+VERTEX_SE2 143 -6.373361 -1.045821 1.369956
+VERTEX_SE2 144 -6.308206 -0.684059 1.387205
+VERTEX_SE2 145 -6.303725 -0.673188 0.888171
+VERTEX_SE2 146 -6.303130 -0.671010 0.294225
+VERTEX_SE2 147 -6.246280 -0.679152 -0.192923
+VERTEX_SE2 148 -5.818303 -0.770932 -0.228866
+VERTEX_SE2 149 -5.184464 -0.911850 -0.204032
+VERTEX_SE2 150 -4.555178 -1.023116 -0.190122
+VERTEX_SE2 151 -3.919217 -1.117808 -0.104723
+VERTEX_SE2 152 -3.282062 -1.199418 -0.172903
+VERTEX_SE2 153 -2.645312 -1.282994 -0.087181
+VERTEX_SE2 154 -2.011150 -1.359207 -0.164419
+VERTEX_SE2 155 -1.375820 -1.453297 -0.137992
+VERTEX_SE2 156 -0.735790 -1.532677 -0.114327
+VERTEX_SE2 157 -0.159947 -1.613323 -0.186690
+VERTEX_SE2 158 0.023851 -1.648467 -0.157600
+VERTEX_SE2 159 0.021228 -1.647288 0.835817
+VERTEX_SE2 160 0.027488 -1.639228 1.877886
+VERTEX_SE2 161 0.027486 -1.639234 2.859828
+VERTEX_SE2 162 0.045975 -1.631965 -2.381155
+VERTEX_SE2 163 0.045893 -1.634205 -1.377922
+VERTEX_SE2 164 0.057499 -1.646265 -0.447964
+VERTEX_SE2 165 0.193934 -1.655710 -0.045831
+VERTEX_SE2 166 0.853469 -1.682017 -0.046800
+VERTEX_SE2 167 1.490484 -1.716964 -0.075973
+VERTEX_SE2 168 2.098800 -1.751671 -0.063936
+VERTEX_SE2 169 2.712806 -1.808931 -0.100989
+VERTEX_SE2 170 3.318192 -1.863258 -0.121905
+VERTEX_SE2 171 3.896234 -1.949098 -0.160646
+VERTEX_SE2 172 4.538410 -2.042425 -0.147172
+VERTEX_SE2 173 5.172424 -2.149723 -0.165214
+VERTEX_SE2 174 5.803089 -2.247662 -0.120052
+VERTEX_SE2 175 6.424807 -2.318550 -0.139998
+VERTEX_SE2 176 7.030678 -2.417232 -0.125711
+VERTEX_SE2 177 7.660479 -2.494551 -0.148623
+VERTEX_SE2 178 8.290147 -2.612123 -0.182806
+VERTEX_SE2 179 8.639509 -2.668503 -0.129585
+VERTEX_SE2 180 8.642601 -2.669171 -0.571750
+VERTEX_SE2 181 9.107062 -2.977761 -0.623138
+VERTEX_SE2 182 9.551340 -3.341562 -0.796106
+VERTEX_SE2 183 9.953562 -3.792478 -0.852123
+VERTEX_SE2 184 10.330878 -4.306658 -1.002936
+VERTEX_SE2 185 10.652963 -4.854256 -1.099221
+VERTEX_SE2 186 10.909459 -5.445570 -1.168989
+VERTEX_SE2 187 11.138453 -6.018162 -1.194573
+VERTEX_SE2 188 11.372847 -6.610777 -1.202696
+VERTEX_SE2 189 11.598101 -7.209159 -1.232095
+VERTEX_SE2 190 11.795596 -7.819838 -1.258284
+VERTEX_SE2 191 11.984938 -8.432395 -1.279246
+VERTEX_SE2 192 12.158054 -9.043198 -1.303901
+VERTEX_SE2 193 12.302583 -9.611434 -1.355161
+VERTEX_SE2 194 12.426909 -10.210284 -1.377141
+VERTEX_SE2 195 12.534319 -10.811416 -1.400368
+VERTEX_SE2 196 12.632338 -11.445843 -1.442220
+VERTEX_SE2 197 12.700713 -12.082422 -1.470453
+VERTEX_SE2 198 12.755597 -12.719166 -1.529113
+VERTEX_SE2 199 12.754761 -13.356843 -1.590711
+VERTEX_SE2 200 12.733560 -13.993458 -1.612475
+VERTEX_SE2 201 12.687026 -14.631689 -1.668718
+VERTEX_SE2 202 12.639077 -15.202899 -1.651577
+VERTEX_SE2 203 12.556158 -16.006543 -1.707054
+VERTEX_SE2 204 12.455302 -16.598850 -1.804142
+VERTEX_SE2 205 12.305924 -17.187841 -1.809172
+VERTEX_SE2 206 12.174405 -17.760149 -1.802549
+VERTEX_SE2 207 12.040676 -18.353284 -1.781423
+VERTEX_SE2 208 11.897670 -18.981299 -1.785518
+VERTEX_SE2 209 11.769917 -19.609340 -1.741125
+VERTEX_SE2 210 11.647398 -20.238835 -1.754048
+VERTEX_SE2 211 11.537207 -20.870318 -1.755716
+VERTEX_SE2 212 11.394970 -21.493361 -1.812926
+VERTEX_SE2 213 11.230953 -22.120731 -1.837752
+VERTEX_SE2 214 11.058372 -22.734177 -1.845436
+VERTEX_SE2 215 10.953834 -23.088866 -1.885350
+VERTEX_SE2 216 10.950554 -23.095138 -2.393113
+VERTEX_SE2 217 10.952753 -23.094815 -2.944927
+VERTEX_SE2 218 10.951809 -23.094487 -3.005204
+VERTEX_SE2 219 10.365803 -23.067344 3.104107
+VERTEX_SE2 220 9.737327 -23.038247 3.059963
+VERTEX_SE2 221 9.095837 -22.994717 3.111718
+VERTEX_SE2 222 8.460944 -22.975047 3.086737
+VERTEX_SE2 223 7.821250 -22.969336 -3.100192
+VERTEX_SE2 224 7.183803 -22.994444 -3.126677
+VERTEX_SE2 225 6.544582 -23.012637 -3.078368
+VERTEX_SE2 226 5.906305 -23.029186 -3.129535
+VERTEX_SE2 227 5.264179 -23.084344 -2.972817
+VERTEX_SE2 228 4.660809 -23.049652 2.951621
+VERTEX_SE2 229 4.059169 -22.969281 3.076549
+VERTEX_SE2 230 3.689211 -22.947652 3.051106
+VERTEX_SE2 231 3.819912 -22.954624 3.124109
+VERTEX_SE2 232 3.476990 -22.813142 2.710350
+VERTEX_SE2 233 2.875321 -22.565879 2.819555
+VERTEX_SE2 234 2.261463 -22.358960 2.781360
+VERTEX_SE2 235 1.979653 -22.255530 2.781875
+VERTEX_SE2 236 1.616344 -22.278805 -3.083673
+VERTEX_SE2 237 0.964219 -22.341873 -3.006771
+VERTEX_SE2 238 0.323899 -22.443278 -3.033605
+VERTEX_SE2 239 -0.317791 -22.494927 -3.094849
+VERTEX_SE2 240 -0.925503 -22.426348 2.978831
+VERTEX_SE2 241 -1.504549 -22.345735 3.071089
+VERTEX_SE2 242 -2.117312 -22.325210 3.098446
+VERTEX_SE2 243 -2.764025 -22.279874 3.087887
+VERTEX_SE2 244 -3.406724 -22.271623 -3.133223
+VERTEX_SE2 245 -4.041131 -22.254659 3.087973
+VERTEX_SE2 246 -4.684337 -22.191483 3.008717
+VERTEX_SE2 247 -5.325218 -22.128855 3.108731
+VERTEX_SE2 248 -5.890123 -22.137360 3.133698
+VERTEX_SE2 249 -5.854210 -22.141017 -2.965499
+VERTEX_SE2 250 -5.862024 -22.141342 2.710834
+VERTEX_SE2 251 -6.210340 -21.788237 2.273028
+VERTEX_SE2 252 -6.584399 -21.351579 2.275461
+VERTEX_SE2 253 -6.971866 -20.886741 2.258217
+VERTEX_SE2 254 -7.349642 -20.406697 2.210371
+VERTEX_SE2 255 -7.376562 -20.371386 2.285362
+VERTEX_SE2 256 -7.376569 -20.370011 1.785796
+VERTEX_SE2 257 -7.435125 -19.813876 1.686629
+VERTEX_SE2 258 -7.526140 -19.190499 1.778261
+VERTEX_SE2 259 -7.676213 -18.571996 1.817167
+VERTEX_SE2 260 -7.815262 -17.997419 1.807084
+VERTEX_SE2 261 -7.812802 -17.957528 1.492756
+VERTEX_SE2 262 -7.748761 -17.305023 1.497634
+VERTEX_SE2 263 -7.704459 -16.684761 1.509160
+VERTEX_SE2 264 -7.686285 -16.075835 1.603801
+VERTEX_SE2 265 -7.713685 -15.464092 1.621756
+VERTEX_SE2 266 -7.659836 -14.884512 1.489698
+VERTEX_SE2 267 -7.590637 -14.130213 1.451229
+VERTEX_SE2 268 -7.434892 -13.512524 1.330524
+VERTEX_SE2 269 -7.285843 -12.888133 1.352351
+VERTEX_SE2 270 -7.181145 -12.258185 1.457078
+VERTEX_SE2 271 -7.046662 -11.629374 1.337392
+VERTEX_SE2 272 -6.916330 -10.998172 1.394889
+VERTEX_SE2 273 -6.887272 -10.359052 1.601643
+VERTEX_SE2 274 -6.914937 -9.718617 1.621477
+VERTEX_SE2 275 -6.859410 -9.108548 1.443918
+VERTEX_SE2 276 -6.805341 -8.498288 1.552614
+VERTEX_SE2 277 -6.805090 -7.914615 1.521694
+VERTEX_SE2 278 -6.706035 -7.282637 1.426405
+VERTEX_SE2 279 -6.600956 -6.648396 1.372248
+VERTEX_SE2 280 -6.468990 -6.023366 1.375327
+VERTEX_SE2 281 -6.315271 -5.399485 1.276051
+VERTEX_SE2 282 -6.134008 -4.785899 1.316907
+VERTEX_SE2 283 -5.985222 -4.161193 1.309959
+VERTEX_SE2 284 -5.813249 -3.550243 1.337990
+VERTEX_SE2 285 -5.683475 -2.918967 1.354789
+VERTEX_SE2 286 -5.554450 -2.315719 1.403911
+VERTEX_SE2 287 -5.547714 -2.274662 1.294491
+VERTEX_SE2 288 -5.541900 -2.266525 0.674528
+VERTEX_SE2 289 -5.522271 -2.259034 0.069939
+VERTEX_SE2 290 -5.061939 -2.331133 -0.161343
+VERTEX_SE2 291 -4.422087 -2.430958 -0.151620
+VERTEX_SE2 292 -3.797538 -2.541567 -0.206901
+VERTEX_SE2 293 -3.169915 -2.679421 -0.230678
+VERTEX_SE2 294 -2.547430 -2.824259 -0.230786
+VERTEX_SE2 295 -1.930374 -2.997710 -0.344395
+VERTEX_SE2 296 -1.332265 -3.234619 -0.390911
+VERTEX_SE2 297 -0.738078 -3.478649 -0.403774
+VERTEX_SE2 298 -0.140714 -3.729757 -0.400411
+VERTEX_SE2 299 0.420679 -3.975672 -0.334750
+VERTEX_SE2 300 1.008544 -4.149557 -0.288323
+VERTEX_SE2 301 1.570135 -4.331714 -0.343252
+VERTEX_SE2 302 1.877809 -4.442855 -0.360266
+VERTEX_SE2 303 1.877809 -4.442855 -0.352308
+VERTEX_SE2 304 2.376686 -4.626875 -0.338959
+VERTEX_SE2 305 3.003258 -4.750507 -0.149877
+VERTEX_SE2 306 3.635522 -4.836601 -0.164412
+VERTEX_SE2 307 4.273138 -4.958970 -0.197471
+VERTEX_SE2 308 4.897872 -5.092864 -0.249303
+VERTEX_SE2 309 5.530724 -5.222563 -0.152307
+VERTEX_SE2 310 6.160264 -5.318301 -0.184629
+VERTEX_SE2 311 6.445365 -5.373694 -0.004883
+VERTEX_SE2 312 6.452735 -5.370466 0.998034
+VERTEX_SE2 313 6.475194 -5.146827 1.501717
+VERTEX_SE2 314 6.500598 -4.513221 1.545236
+VERTEX_SE2 315 6.514519 -3.879666 1.544361
+VERTEX_SE2 316 6.515603 -3.240166 1.596992
+VERTEX_SE2 317 6.494598 -2.602753 1.608134
+VERTEX_SE2 318 6.435460 -1.967773 1.704091
+VERTEX_SE2 319 6.377663 -1.623559 1.776803
+VERTEX_SE2 320 6.378012 -1.622652 2.750031
+VERTEX_SE2 321 6.369361 -1.625849 -2.488361
+VERTEX_SE2 322 6.365946 -1.632038 -1.487277
+VERTEX_SE2 323 6.380435 -1.647235 -0.490000
+VERTEX_SE2 324 6.388880 -1.650346 0.173199
+VERTEX_SE2 325 6.392046 -1.650203 -0.351692
+VERTEX_SE2 326 6.411655 -1.665878 -0.943866
+VERTEX_SE2 327 6.415870 -1.688728 -1.564092
+VERTEX_SE2 328 6.385292 -2.332605 -1.609333
+VERTEX_SE2 329 6.349431 -2.981039 -1.664005
+VERTEX_SE2 330 6.281461 -3.617106 -1.682877
+VERTEX_SE2 331 6.213453 -4.254537 -1.697056
+VERTEX_SE2 332 6.121245 -4.888223 -1.715483
+VERTEX_SE2 333 6.093922 -5.063750 -1.650313
+VERTEX_SE2 334 6.091827 -5.064491 -0.592795
+VERTEX_SE2 335 6.120861 -5.065606 0.404271
+VERTEX_SE2 336 6.129696 -5.059618 1.351179
+VERTEX_SE2 337 6.128718 -5.050440 2.336187
+VERTEX_SE2 338 6.132587 -5.051833 -2.965274
+VERTEX_SE2 339 6.136968 -5.047185 -1.923597
+VERTEX_SE2 340 6.142971 -5.060659 -0.911817
+VERTEX_SE2 341 6.275970 -5.101488 -0.283246
+VERTEX_SE2 342 6.910811 -5.263299 -0.183431
+VERTEX_SE2 343 7.538989 -5.324161 -0.052630
+VERTEX_SE2 344 8.173624 -5.364758 -0.062705
+VERTEX_SE2 345 8.440897 -5.378047 -0.090243
+VERTEX_SE2 346 8.445372 -5.378415 -0.737666
+VERTEX_SE2 347 8.467770 -5.462068 -1.296495
+VERTEX_SE2 348 8.621467 -6.030776 -1.313338
+VERTEX_SE2 349 8.761762 -6.631679 -1.353796
+VERTEX_SE2 350 8.929986 -7.398958 -1.373714
+VERTEX_SE2 351 8.978041 -7.665351 -1.403006
+VERTEX_SE2 352 8.978090 -7.667619 -1.691302
+VERTEX_SE2 353 8.976498 -7.670853 -2.356727
+VERTEX_SE2 354 8.981756 -7.667962 -2.960124
+VERTEX_SE2 355 8.981756 -7.667962 2.602071
+VERTEX_SE2 356 8.978992 -7.664902 2.026818
+VERTEX_SE2 357 8.977837 -7.643021 1.373746
+VERTEX_SE2 358 8.983884 -7.628618 0.758292
+VERTEX_SE2 359 8.989631 -7.624545 0.144263
+VERTEX_SE2 360 8.994126 -7.624478 -0.032038
+VERTEX_SE2 361 9.004896 -7.619118 0.887338
+VERTEX_SE2 362 9.042246 -7.366063 1.421081
+VERTEX_SE2 363 9.090049 -7.072841 1.414605
+VERTEX_SE2 364 8.954880 -6.758641 2.029221
+VERTEX_SE2 365 8.843129 -6.487231 1.532139
+VERTEX_SE2 366 8.933049 -6.331605 0.978068
+VERTEX_SE2 367 9.294391 -5.803956 0.980155
+VERTEX_SE2 368 9.641307 -5.309201 0.927211
+VERTEX_SE2 369 9.642383 -5.307246 0.668025
+VERTEX_SE2 370 9.648356 -5.305144 0.068704
+VERTEX_SE2 371 9.655229 -5.307316 -0.488502
+VERTEX_SE2 372 10.139103 -5.587085 -0.520850
+VERTEX_SE2 373 10.666751 -5.878088 -0.523177
+VERTEX_SE2 374 11.206068 -6.209159 -0.589126
+VERTEX_SE2 375 11.598593 -6.466633 -0.617897
+VERTEX_SE2 376 11.600632 -6.467490 0.080627
+VERTEX_SE2 377 11.643620 -6.425565 0.779646
+VERTEX_SE2 378 12.107190 -5.948151 0.834726
+VERTEX_SE2 379 12.510240 -5.446009 0.920455
+VERTEX_SE2 380 12.867606 -4.912917 1.040753
+VERTEX_SE2 381 12.982544 -4.709680 1.191659
+VERTEX_SE2 382 12.984649 -4.703709 2.244782
+VERTEX_SE2 383 12.988448 -4.705226 -3.058347
+VERTEX_SE2 384 12.986650 -4.707628 -2.101256
+VERTEX_SE2 385 12.982495 -4.718256 -1.078274
+VERTEX_SE2 386 13.111397 -4.840399 -0.855882
+VERTEX_SE2 387 13.631915 -5.191372 -0.527133
+VERTEX_SE2 388 14.188298 -5.499440 -0.516375
+VERTEX_SE2 389 14.722428 -5.830510 -0.596695
+VERTEX_SE2 390 14.780394 -5.868314 -0.117993
+VERTEX_SE2 391 14.643686 -5.885580 0.265004
+VERTEX_SE2 392 14.640989 -5.886114 1.312766
+VERTEX_SE2 393 14.635188 -5.855400 2.572219
+VERTEX_SE2 394 14.626068 -5.853862 -2.712409
+VERTEX_SE2 395 14.810464 -5.693039 -2.372812
+VERTEX_SE2 396 14.810464 -5.693039 -2.371562
+VERTEX_SE2 397 14.809202 -5.693678 -2.381203
+VERTEX_SE2 398 14.806796 -5.697007 -2.182098
+VERTEX_SE2 399 14.762364 -5.814932 -1.881357
+VERTEX_SE2 400 14.564819 -6.441727 -1.829942
+VERTEX_SE2 401 14.377600 -7.049960 -1.921842
+VERTEX_SE2 402 14.049396 -7.600148 -2.188305
+VERTEX_SE2 403 13.678588 -8.113304 -2.221999
+VERTEX_SE2 404 13.306297 -8.574268 -2.300702
+VERTEX_SE2 405 13.304585 -8.576945 -1.766179
+VERTEX_SE2 406 13.302371 -8.571544 -0.786819
+VERTEX_SE2 407 13.585994 -8.797369 -0.658504
+VERTEX_SE2 408 14.069560 -9.180165 -0.696311
+VERTEX_SE2 409 14.292699 -9.377696 -0.795739
+VERTEX_SE2 410 14.294947 -9.381536 -1.423249
+VERTEX_SE2 411 14.294896 -9.380539 -2.012202
+VERTEX_SE2 412 13.969601 -9.830799 -2.215053
+VERTEX_SE2 413 13.573781 -10.323212 -2.294584
+VERTEX_SE2 414 13.168212 -10.809845 -2.190851
+VERTEX_SE2 415 12.788348 -11.328437 -2.184168
+VERTEX_SE2 416 12.618672 -11.583273 -2.239720
+VERTEX_SE2 417 12.365589 -11.724804 -2.664770
+VERTEX_SE2 418 11.973570 -11.921372 -2.710238
+VERTEX_SE2 419 11.979618 -11.915306 -2.279799
+VERTEX_SE2 420 12.016291 -11.860711 -2.064037
+VERTEX_SE2 421 12.016287 -11.845604 -1.097383
+VERTEX_SE2 422 12.016575 -11.841230 0.140539
+VERTEX_SE2 423 12.021144 -11.838978 0.485675
+VERTEX_SE2 424 12.021144 -11.838978 0.485954
+VERTEX_SE2 425 12.020459 -11.840215 0.497589
+VERTEX_SE2 426 12.020459 -11.840215 0.488372
+VERTEX_SE2 427 12.049082 -11.824671 0.491399
+VERTEX_SE2 428 12.625045 -11.496891 0.485740
+VERTEX_SE2 429 13.200413 -11.202813 0.444713
+VERTEX_SE2 430 13.512701 -11.059854 0.398340
+VERTEX_SE2 431 13.491669 -11.069431 0.449977
+VERTEX_SE2 432 13.501654 -11.067336 -0.182740
+VERTEX_SE2 433 13.502954 -11.067884 -0.861102
+VERTEX_SE2 434 13.743529 -11.537644 -1.089862
+VERTEX_SE2 435 14.040604 -12.094609 -1.118566
+VERTEX_SE2 436 14.297216 -12.672347 -1.127731
+VERTEX_SE2 437 14.580075 -13.245886 -1.120167
+VERTEX_SE2 438 14.774602 -13.672697 -1.152842
+VERTEX_SE2 439 14.775466 -13.675785 -1.592980
+VERTEX_SE2 440 14.781226 -13.661057 -2.241615
+VERTEX_SE2 441 14.801541 -13.646476 -2.868987
+VERTEX_SE2 442 14.816809 -13.646193 2.779417
+VERTEX_SE2 443 14.817345 -13.647038 2.207553
+VERTEX_SE2 444 14.811569 -13.629249 1.610879
+VERTEX_SE2 445 14.815891 -13.615770 0.947107
+VERTEX_SE2 446 14.818888 -13.610711 1.145697
+VERTEX_SE2 447 14.818661 -13.580487 1.771810
+VERTEX_SE2 448 14.666760 -12.956104 1.786852
+VERTEX_SE2 449 14.494693 -12.326428 1.885308
+VERTEX_SE2 450 14.289690 -11.713731 1.896557
+VERTEX_SE2 451 14.124257 -11.267884 1.936509
+VERTEX_SE2 452 14.123115 -11.264972 1.553661
+VERTEX_SE2 453 14.123047 -11.266384 0.924731
+VERTEX_SE2 454 14.355665 -11.130372 0.497531
+VERTEX_SE2 455 14.885259 -10.850245 0.477764
+VERTEX_SE2 456 15.454443 -10.572873 0.414138
+VERTEX_SE2 457 15.786015 -10.438633 0.327481
+VERTEX_SE2 458 15.795226 -10.438701 -0.315965
+VERTEX_SE2 459 15.791330 -10.434037 -0.921822
+VERTEX_SE2 460 15.959734 -10.828507 -1.177398
+VERTEX_SE2 461 16.180144 -11.439953 -1.264281
+VERTEX_SE2 462 16.335308 -11.963645 -1.303337
+VERTEX_SE2 463 16.335291 -11.965068 -0.460067
+VERTEX_SE2 464 16.605696 -11.914838 0.220623
+VERTEX_SE2 465 17.195283 -11.771695 0.229379
+VERTEX_SE2 466 17.767104 -11.657874 0.174926
+VERTEX_SE2 467 18.369280 -11.563197 0.132707
+VERTEX_SE2 468 19.009735 -11.482106 0.096378
+VERTEX_SE2 469 19.650896 -11.453733 0.012587
+VERTEX_SE2 470 20.146853 -11.442829 0.030741
+VERTEX_SE2 471 20.150029 -11.442932 -0.170062
+VERTEX_SE2 472 20.172311 -11.454699 -0.804400
+VERTEX_SE2 473 20.175889 -11.459298 -1.446679
+VERTEX_SE2 474 20.174399 -11.466191 -2.079685
+VERTEX_SE2 475 20.170246 -11.468957 -2.655668
+VERTEX_SE2 476 20.165497 -11.470500 2.973880
+VERTEX_SE2 477 20.170525 -11.474309 2.412190
+VERTEX_SE2 478 20.175145 -11.482300 1.782778
+VERTEX_SE2 479 20.175335 -11.487697 1.326596
+VERTEX_SE2 480 20.175383 -11.489918 1.886460
+VERTEX_SE2 481 20.164295 -11.475887 2.884919
+VERTEX_SE2 482 20.162062 -11.476008 -3.063751
+VERTEX_SE2 483 20.162062 -11.476008 -3.070064
+VERTEX_SE2 484 19.701970 -11.512371 -3.035533
+VERTEX_SE2 485 19.076677 -11.593317 -3.038332
+VERTEX_SE2 486 18.439371 -11.653164 -3.029341
+VERTEX_SE2 487 17.807280 -11.746714 -3.001669
+VERTEX_SE2 488 17.172291 -11.839127 -2.966212
+VERTEX_SE2 489 16.696147 -11.938931 -2.936476
+VERTEX_SE2 490 16.692490 -11.941051 -2.452793
+VERTEX_SE2 491 16.691616 -11.944932 -1.519098
+VERTEX_SE2 492 16.776617 -12.175290 -1.217149
+VERTEX_SE2 493 16.974062 -12.765556 -1.272900
+VERTEX_SE2 494 17.150447 -13.373462 -1.334510
+VERTEX_SE2 495 17.352115 -13.978346 -1.223707
+VERTEX_SE2 496 17.581624 -14.577196 -1.102707
+VERTEX_SE2 497 17.847299 -15.159575 -1.186084
+VERTEX_SE2 498 18.054425 -15.760767 -1.285551
+VERTEX_SE2 499 18.205483 -16.382164 -1.300921
+VERTEX_SE2 500 18.520086 -16.898620 -0.969638
+VERTEX_SE2 501 18.848430 -17.411482 -1.035455
+VERTEX_SE2 502 19.181866 -18.047877 -1.113614
+VERTEX_SE2 503 19.382829 -18.470616 -1.125142
+VERTEX_SE2 504 19.382968 -18.471669 -0.242877
+VERTEX_SE2 505 19.636847 -18.373822 0.396037
+VERTEX_SE2 506 20.222463 -18.152233 0.250781
+VERTEX_SE2 507 20.842906 -18.012083 0.178603
+VERTEX_SE2 508 21.473389 -17.912172 0.170945
+VERTEX_SE2 509 22.107555 -17.811551 0.119274
+VERTEX_SE2 510 22.477732 -17.773275 0.109324
+VERTEX_SE2 511 22.480191 -17.776579 1.000327
+VERTEX_SE2 512 22.479151 -17.767197 2.221724
+VERTEX_SE2 513 22.480923 -17.768589 -3.088724
+VERTEX_SE2 514 22.392210 -17.797083 -2.856452
+VERTEX_SE2 515 21.763760 -17.994866 -2.851524
+VERTEX_SE2 516 21.150540 -18.168893 -2.831780
+VERTEX_SE2 517 20.555780 -18.389856 -2.799728
+VERTEX_SE2 518 19.960512 -18.610158 -2.771638
+VERTEX_SE2 519 19.439217 -18.815169 -2.783788
+VERTEX_SE2 520 19.254408 -18.883689 -2.378354
+VERTEX_SE2 521 19.253544 -18.891468 -1.358862
+VERTEX_SE2 522 19.446557 -19.274210 -1.088837
+VERTEX_SE2 523 19.743533 -19.846628 -1.102099
+VERTEX_SE2 524 20.002482 -20.395419 -1.149751
+VERTEX_SE2 525 20.240546 -20.920829 -1.130979
+VERTEX_SE2 526 20.481533 -21.478440 -1.194565
+VERTEX_SE2 527 20.701007 -22.071838 -1.233424
+VERTEX_SE2 528 20.883349 -22.686071 -1.313266
+VERTEX_SE2 529 21.048790 -23.294125 -1.338785
+VERTEX_SE2 530 21.186548 -23.922294 -1.365903
+VERTEX_SE2 531 21.294513 -24.545568 -1.442267
+VERTEX_SE2 532 21.321981 -24.753969 -1.388289
+VERTEX_SE2 533 21.331696 -24.762834 -0.381514
+VERTEX_SE2 534 21.336665 -24.762597 0.290307
+VERTEX_SE2 535 21.336665 -24.762597 0.291645
+VERTEX_SE2 536 21.667408 -24.621679 0.424610
+VERTEX_SE2 537 22.237616 -24.383793 0.368660
+VERTEX_SE2 538 22.783578 -24.188298 0.343558
+VERTEX_SE2 539 23.392496 -23.994630 0.281055
+VERTEX_SE2 540 24.012651 -23.846863 0.190656
+VERTEX_SE2 541 24.616500 -23.677520 0.355935
+VERTEX_SE2 542 25.198874 -23.413487 0.414186
+VERTEX_SE2 543 25.308230 -23.366534 0.386937
+VERTEX_SE2 544 25.311458 -23.363477 1.030295
+VERTEX_SE2 545 25.308953 -23.348021 2.106974
+VERTEX_SE2 546 25.370099 -23.384281 2.942044
+VERTEX_SE2 547 25.364196 -23.389842 -2.309543
+VERTEX_SE2 548 25.360603 -23.401304 -1.377667
+VERTEX_SE2 549 25.371198 -23.418104 -0.563163
+VERTEX_SE2 550 25.376228 -23.423323 -1.037842
+VERTEX_SE2 551 25.379648 -23.436304 -1.657979
+VERTEX_SE2 552 25.377719 -23.441024 -2.284180
+VERTEX_SE2 553 25.238021 -23.493388 -2.855731
+VERTEX_SE2 554 24.607784 -23.677279 -2.888859
+VERTEX_SE2 555 23.993431 -23.860841 -2.797492
+VERTEX_SE2 556 23.396241 -24.105763 -2.659796
+VERTEX_SE2 557 22.822728 -24.393516 -2.702744
+VERTEX_SE2 558 22.275040 -24.674698 -2.623823
+VERTEX_SE2 559 22.270077 -24.676821 -3.034381
+VERTEX_SE2 560 22.270077 -24.676821 2.743761
+VERTEX_SE2 561 22.260080 -24.676351 -3.038320
+VERTEX_SE2 562 22.096754 -24.820650 -2.399936
+VERTEX_SE2 563 21.592502 -25.154311 -2.594747
+VERTEX_SE2 564 21.053412 -25.498706 -2.548499
+VERTEX_SE2 565 20.537425 -25.832798 -2.600465
+VERTEX_SE2 566 20.532490 -25.835035 -1.796294
+VERTEX_SE2 567 20.533426 -25.833987 -0.940208
+VERTEX_SE2 568 20.891388 -26.294540 -0.894012
+VERTEX_SE2 569 21.276856 -26.790552 -0.946159
+VERTEX_SE2 570 21.649420 -27.310717 -0.950967
+VERTEX_SE2 571 21.849361 -27.596250 -0.994364
+VERTEX_SE2 572 21.840333 -27.646492 -1.231717
+VERTEX_SE2 573 21.868880 -27.724009 -0.949072
+VERTEX_SE2 574 21.877216 -27.725452 0.006744
+VERTEX_SE2 575 21.894503 -27.715687 1.016050
+VERTEX_SE2 576 21.893519 -27.715892 2.040189
+VERTEX_SE2 577 21.885895 -27.713246 3.008947
+VERTEX_SE2 578 21.866274 -27.704702 2.643177
+VERTEX_SE2 579 21.298924 -27.387881 2.657278
+VERTEX_SE2 580 20.716909 -27.105551 2.731333
+VERTEX_SE2 581 20.125767 -26.856860 2.772637
+VERTEX_SE2 582 19.523535 -26.633599 2.814640
+VERTEX_SE2 583 19.213810 -26.536403 2.892766
+VERTEX_SE2 584 19.210319 -26.535584 -2.550218
+VERTEX_SE2 585 18.716874 -26.893765 -2.433208
+VERTEX_SE2 586 18.264978 -27.304159 -2.336932
+VERTEX_SE2 587 17.844050 -27.776684 -2.312675
+VERTEX_SE2 588 17.404102 -28.246717 -2.309353
+VERTEX_SE2 589 17.007668 -28.742973 -2.229083
+VERTEX_SE2 590 16.625023 -29.262060 -2.155304
+VERTEX_SE2 591 16.286319 -29.796280 -2.152683
+VERTEX_SE2 592 15.939159 -30.336565 -2.150686
+VERTEX_SE2 593 15.791190 -30.564791 -1.938181
+VERTEX_SE2 594 15.794250 -30.581455 -0.945084
+VERTEX_SE2 595 16.194292 -30.997078 -0.704760
+VERTEX_SE2 596 16.636104 -31.366417 -0.722635
+VERTEX_SE2 597 17.103989 -31.796447 -0.756770
+VERTEX_SE2 598 17.538795 -32.215917 -0.796372
+VERTEX_SE2 599 17.800839 -32.499098 -0.859831
+VERTEX_SE2 600 17.808423 -32.504032 -0.045074
+VERTEX_SE2 601 17.830600 -32.493623 0.983541
+VERTEX_SE2 602 17.834247 -32.474305 2.007952
+VERTEX_SE2 603 17.607884 -32.374428 2.788384
+VERTEX_SE2 604 17.046943 -32.100473 2.547892
+VERTEX_SE2 605 16.511286 -31.761753 2.630512
+VERTEX_SE2 606 15.949994 -31.464096 2.672598
+VERTEX_SE2 607 15.464785 -31.153778 2.591564
+VERTEX_SE2 608 15.140800 -30.969820 2.636022
+VERTEX_SE2 609 15.131468 -30.966068 2.972317
+VERTEX_SE2 610 15.122044 -30.973580 -2.378251
+VERTEX_SE2 611 14.678938 -31.406105 -2.375287
+VERTEX_SE2 612 14.313602 -31.741587 -2.372510
+VERTEX_SE2 613 14.338061 -31.720011 -1.908805
+VERTEX_SE2 614 14.338698 -31.726674 -0.870968
+VERTEX_SE2 615 14.768768 -31.977559 -0.566453
+VERTEX_SE2 616 15.311642 -32.305648 -0.617609
+VERTEX_SE2 617 15.760313 -32.746217 -0.834639
+VERTEX_SE2 618 16.193436 -33.214065 -0.824521
+VERTEX_SE2 619 16.601337 -33.656810 -0.825989
+VERTEX_SE2 620 17.000072 -34.120401 -0.922318
+VERTEX_SE2 621 16.788426 -33.839458 -0.973924
+VERTEX_SE2 622 16.630958 -33.597689 -1.048966
+VERTEX_SE2 623 16.629619 -33.594321 -1.586115
+VERTEX_SE2 624 16.631309 -33.591662 -2.228805
+VERTEX_SE2 625 16.624999 -33.596266 -2.887438
+VERTEX_SE2 626 16.617480 -33.597475 2.777619
+VERTEX_SE2 627 16.349285 -33.346497 2.366813
+VERTEX_SE2 628 15.919513 -32.868045 2.265896
+VERTEX_SE2 629 15.485805 -32.395397 2.336946
+VERTEX_SE2 630 15.046318 -31.973583 2.422035
+VERTEX_SE2 631 14.646636 -31.639639 2.442255
+VERTEX_SE2 632 14.643929 -31.637238 3.118464
+VERTEX_SE2 633 14.589597 -31.712326 -2.089116
+VERTEX_SE2 634 14.266192 -32.277649 -2.063889
+VERTEX_SE2 635 13.925936 -32.819825 -2.201180
+VERTEX_SE2 636 13.554818 -33.335756 -2.220264
+VERTEX_SE2 637 13.147645 -33.820778 -2.320948
+VERTEX_SE2 638 12.855265 -34.121161 -2.351695
+VERTEX_SE2 639 12.424371 -34.596136 -2.272930
+VERTEX_SE2 640 11.985578 -35.070016 -2.342632
+VERTEX_SE2 641 11.552638 -35.529379 -2.352802
+VERTEX_SE2 642 11.112191 -35.949492 -2.400353
+VERTEX_SE2 643 10.731895 -36.277399 -2.465381
+VERTEX_SE2 644 10.729340 -36.284109 -1.701776
+VERTEX_SE2 645 10.869715 -36.451460 -0.744873
+VERTEX_SE2 646 11.382066 -36.817597 -0.447477
+VERTEX_SE2 647 11.978978 -37.021611 -0.156322
+VERTEX_SE2 648 12.612056 -37.054234 0.012089
+VERTEX_SE2 649 13.205551 -37.119561 -0.322437
+VERTEX_SE2 650 13.749716 -37.452144 -0.576811
+VERTEX_SE2 651 13.876986 -37.522144 0.229018
+VERTEX_SE2 652 13.879256 -37.519914 1.262617
+VERTEX_SE2 653 13.872372 -37.502026 2.301465
+VERTEX_SE2 654 13.581181 -37.403460 2.818912
+VERTEX_SE2 655 13.048482 -37.219840 2.815600
+VERTEX_SE2 656 12.474722 -37.010334 2.804516
+VERTEX_SE2 657 11.844104 -36.899464 3.083365
+VERTEX_SE2 658 11.204549 -36.869297 3.076381
+VERTEX_SE2 659 10.709556 -36.810477 3.005332
+VERTEX_SE2 660 10.703219 -36.809512 -2.677502
+VERTEX_SE2 661 10.609221 -37.000250 -2.023854
+VERTEX_SE2 662 10.337163 -37.568215 -1.954223
+VERTEX_SE2 663 10.139552 -38.159090 -1.853215
+VERTEX_SE2 664 10.135226 -38.165415 -1.314901
+VERTEX_SE2 665 10.170577 -38.183639 -0.436050
+VERTEX_SE2 666 10.743964 -38.430041 -0.401598
+VERTEX_SE2 667 11.280508 -38.651643 -0.399484
+VERTEX_SE2 668 11.840921 -38.888748 -0.376305
+VERTEX_SE2 669 12.435464 -39.121854 -0.404047
+VERTEX_SE2 670 13.006910 -39.403898 -0.466305
+VERTEX_SE2 671 13.282608 -39.541377 -0.414044
+VERTEX_SE2 672 12.769426 -39.275957 -0.506105
+VERTEX_SE2 673 12.545541 -39.138628 -0.639846
+VERTEX_SE2 674 12.542473 -39.133012 -1.294945
+VERTEX_SE2 675 12.544204 -39.117309 -1.910166
+VERTEX_SE2 676 12.549939 -39.112303 -2.540226
+VERTEX_SE2 677 12.562810 -39.108340 3.120460
+VERTEX_SE2 678 12.373080 -39.013683 2.669222
+VERTEX_SE2 679 11.859571 -38.764102 2.729006
+VERTEX_SE2 680 11.438738 -38.641448 3.069344
+VERTEX_SE2 681 10.825052 -38.579071 3.043558
+VERTEX_SE2 682 10.191857 -38.531816 3.093190
+VERTEX_SE2 683 9.891918 -38.522270 -3.028351
+VERTEX_SE2 684 9.884198 -38.525775 -1.959011
+VERTEX_SE2 685 9.893810 -38.971112 -1.519535
+VERTEX_SE2 686 9.862204 -39.454619 -1.666211
+VERTEX_SE2 687 9.788467 -40.084236 -1.702984
+VERTEX_SE2 688 9.681861 -40.709183 -1.716237
+VERTEX_SE2 689 9.605655 -41.306367 -1.689887
+VERTEX_SE2 690 9.568647 -41.883115 -1.616935
+VERTEX_SE2 691 9.547797 -42.313693 -1.645939
+VERTEX_SE2 692 9.547338 -42.304642 -1.113930
+VERTEX_SE2 693 9.542348 -42.304320 -0.077783
+VERTEX_SE2 694 9.537355 -42.304058 0.754255
+VERTEX_SE2 695 9.537558 -42.302067 1.551174
+VERTEX_SE2 696 9.534841 -42.288755 2.572731
+VERTEX_SE2 697 9.523163 -42.279299 2.318206
+VERTEX_SE2 698 9.451431 -41.889589 1.660453
+VERTEX_SE2 699 9.371393 -41.248546 1.772879
+VERTEX_SE2 700 9.226326 -40.627573 1.824729
+VERTEX_SE2 701 9.049173 -40.073867 1.881983
+VERTEX_SE2 702 8.937709 -39.503989 1.764440
+VERTEX_SE2 703 8.820349 -38.895181 1.796436
+VERTEX_SE2 704 8.652821 -38.280287 1.812200
+VERTEX_SE2 705 8.469818 -37.662927 1.876685
+VERTEX_SE2 706 8.352303 -37.160636 1.599049
+VERTEX_SE2 707 8.353815 -37.156710 1.065513
+VERTEX_SE2 708 8.350433 -37.159057 0.410972
+VERTEX_SE2 709 8.285591 -37.179408 0.069240
+VERTEX_SE2 710 8.271325 -37.178203 -0.506017
+VERTEX_SE2 711 8.272256 -37.177853 -1.117758
+VERTEX_SE2 712 8.271421 -37.172816 -1.692402
+VERTEX_SE2 713 8.082147 -37.631033 -1.986694
+VERTEX_SE2 714 7.781665 -38.118818 -2.191858
+VERTEX_SE2 715 7.436278 -38.650634 -2.086627
+VERTEX_SE2 716 7.101560 -39.196310 -2.222833
+VERTEX_SE2 717 6.732648 -39.710336 -2.136309
+VERTEX_SE2 718 6.249991 -40.323558 -2.309481
+VERTEX_SE2 719 5.841996 -40.813346 -2.233064
+VERTEX_SE2 720 5.439595 -41.301667 -2.290296
+VERTEX_SE2 721 5.032639 -41.793490 -2.219961
+VERTEX_SE2 722 5.017459 -41.813716 -2.151150
+VERTEX_SE2 723 5.020505 -41.823419 -1.052793
+VERTEX_SE2 724 5.031411 -41.829247 0.024382
+VERTEX_SE2 725 5.041952 -41.823519 0.663795
+VERTEX_SE2 726 5.186097 -41.536150 1.121855
+VERTEX_SE2 727 5.441157 -40.953385 1.154429
+VERTEX_SE2 728 5.708786 -40.374749 1.157456
+VERTEX_SE2 729 5.942746 -39.779976 1.216830
+VERTEX_SE2 730 6.141286 -39.181998 1.255908
+VERTEX_SE2 731 6.337960 -38.578088 1.269244
+VERTEX_SE2 732 6.370731 -38.458677 1.718146
+VERTEX_SE2 733 6.369310 -38.458803 2.719136
+VERTEX_SE2 734 5.849568 -38.267284 2.798462
+VERTEX_SE2 735 5.287090 -38.058027 2.767482
+VERTEX_SE2 736 5.282360 -38.056088 -2.913613
+VERTEX_SE2 737 5.275781 -38.066121 -2.109607
+VERTEX_SE2 738 4.978024 -38.585828 -2.089531
+VERTEX_SE2 739 4.620518 -39.102322 -2.146106
+VERTEX_SE2 740 4.357016 -39.553955 -2.081799
+VERTEX_SE2 741 4.357431 -39.553064 -2.448926
+VERTEX_SE2 742 4.347527 -39.558696 -3.099199
+VERTEX_SE2 743 4.342558 -39.557580 2.569578
+VERTEX_SE2 744 4.336078 -39.550170 2.032393
+VERTEX_SE2 745 4.335980 -39.547933 1.441244
+VERTEX_SE2 746 4.573919 -39.080308 0.968419
+VERTEX_SE2 747 4.940154 -38.557294 0.934212
+VERTEX_SE2 748 5.302092 -38.106400 0.867038
+VERTEX_SE2 749 5.345738 -38.052022 1.298344
+VERTEX_SE2 750 5.342230 -38.047361 2.229268
+VERTEX_SE2 751 5.083575 -37.967511 2.872246
+VERTEX_SE2 752 4.493353 -37.766114 2.770046
+VERTEX_SE2 753 3.897446 -37.540993 2.834236
+VERTEX_SE2 754 3.312644 -37.288841 2.673214
+VERTEX_SE2 755 2.737782 -37.020556 2.749498
+VERTEX_SE2 756 2.174638 -36.731322 2.558054
+VERTEX_SE2 757 1.632084 -36.401074 2.656949
+VERTEX_SE2 758 1.085717 -36.165115 2.783429
+VERTEX_SE2 759 0.594312 -35.911010 2.644238
+VERTEX_SE2 760 0.049628 -35.662561 2.758388
+VERTEX_SE2 761 0.027544 -35.652794 2.941901
+VERTEX_SE2 762 0.026506 -35.653762 -2.331733
+VERTEX_SE2 763 -0.256374 -36.186295 -2.039623
+VERTEX_SE2 764 -0.462375 -36.581571 -2.067616
+VERTEX_SE2 765 -0.464849 -36.589741 -1.429340
+VERTEX_SE2 766 -0.458452 -36.594227 -0.430727
+VERTEX_SE2 767 -0.455458 -36.594045 0.498539
+VERTEX_SE2 768 -0.452643 -36.586959 1.219631
+VERTEX_SE2 769 -0.342345 -35.973305 1.375930
+VERTEX_SE2 770 -0.198947 -35.353053 1.308266
+VERTEX_SE2 771 -0.182607 -35.284960 1.867596
+VERTEX_SE2 772 -0.189467 -35.280006 2.733492
+VERTEX_SE2 773 -0.733580 -35.074067 2.818690
+VERTEX_SE2 774 -1.260348 -34.911848 2.840206
+VERTEX_SE2 775 -1.264437 -34.911446 -2.599985
+VERTEX_SE2 776 -1.363996 -35.119485 -1.984041
+VERTEX_SE2 777 -1.608279 -35.704951 -1.925618
+VERTEX_SE2 778 -1.822302 -36.299953 -1.947124
+VERTEX_SE2 779 -2.047440 -36.894571 -1.929730
+VERTEX_SE2 780 -2.139238 -37.102862 -2.060860
+VERTEX_SE2 781 -2.145402 -37.110533 -2.636030
+VERTEX_SE2 782 -2.437259 -37.141405 -3.067105
+VERTEX_SE2 783 -3.047824 -37.175458 -3.068514
+VERTEX_SE2 784 -3.287219 -37.194026 -3.090710
+VERTEX_SE2 785 -3.295317 -37.191509 2.638474
+VERTEX_SE2 786 -3.298918 -37.188857 2.048008
+VERTEX_SE2 787 -3.298039 -37.190654 1.555448
+VERTEX_SE2 788 -3.294912 -37.183493 0.924060
+VERTEX_SE2 789 -3.288075 -37.179210 0.370053
+VERTEX_SE2 790 -2.810788 -37.026036 0.301996
+VERTEX_SE2 791 -2.219090 -36.811172 0.399811
+VERTEX_SE2 792 -1.939736 -36.661187 1.102401
+VERTEX_SE2 793 -1.678873 -36.103497 1.143891
+VERTEX_SE2 794 -1.429675 -35.516238 1.211715
+VERTEX_SE2 795 -1.418449 -35.555793 1.634956
+VERTEX_SE2 796 -1.418085 -35.571576 2.285912
+VERTEX_SE2 797 -1.667269 -35.397655 2.541335
+VERTEX_SE2 798 -2.187789 -35.048694 2.588216
+VERTEX_SE2 799 -2.741194 -34.735022 2.650579
+VERTEX_SE2 800 -3.307545 -34.448654 2.720068
+VERTEX_SE2 801 -3.902341 -34.216184 2.802965
+VERTEX_SE2 802 -4.505679 -34.024853 2.857856
+VERTEX_SE2 803 -5.085804 -33.763383 2.689794
+VERTEX_SE2 804 -5.662771 -33.497682 2.743005
+VERTEX_SE2 805 -6.261534 -33.279468 2.816554
+VERTEX_SE2 806 -6.840015 -33.097367 2.855463
+VERTEX_SE2 807 -7.023476 -33.048729 -3.135502
+VERTEX_SE2 808 -7.026802 -33.056076 -2.177404
+VERTEX_SE2 809 -7.281242 -33.594521 -2.029487
+VERTEX_SE2 810 -7.631595 -34.121859 -2.166451
+VERTEX_SE2 811 -7.962424 -34.637653 -2.167266
+VERTEX_SE2 812 -7.965744 -34.642706 -1.427803
+VERTEX_SE2 813 -7.950068 -34.658744 -0.442321
+VERTEX_SE2 814 -7.946972 -34.656894 0.560269
+VERTEX_SE2 815 -7.933401 -34.640091 1.489098
+VERTEX_SE2 816 -7.934735 -34.631584 2.177465
+VERTEX_SE2 817 -7.937452 -34.619639 1.515677
+VERTEX_SE2 818 -7.834770 -34.423652 1.032291
+VERTEX_SE2 819 -7.526530 -33.907724 1.048948
+VERTEX_SE2 820 -7.214976 -33.390015 1.010358
+VERTEX_SE2 821 -6.920703 -32.916256 1.028688
+VERTEX_SE2 822 -6.919798 -32.914444 1.802164
+VERTEX_SE2 823 -6.939217 -32.906160 2.735576
+VERTEX_SE2 824 -7.523314 -32.665202 2.656921
+VERTEX_SE2 825 -8.081019 -32.349406 2.627743
+VERTEX_SE2 826 -8.677362 -32.112604 2.791147
+VERTEX_SE2 827 -9.263427 -31.871967 2.742741
+VERTEX_SE2 828 -9.860125 -31.638542 2.778381
+VERTEX_SE2 829 -10.419194 -31.408540 2.739767
+VERTEX_SE2 830 -10.979677 -31.164322 2.732511
+VERTEX_SE2 831 -11.504644 -30.911305 2.686863
+VERTEX_SE2 832 -12.017274 -30.666706 2.684351
+VERTEX_SE2 833 -12.247951 -30.553587 2.823368
+VERTEX_SE2 834 -12.252957 -30.553546 -2.400674
+VERTEX_SE2 835 -12.257933 -30.565509 -1.619664
+VERTEX_SE2 836 -12.250730 -30.581427 -0.672599
+VERTEX_SE2 837 -12.229702 -30.583353 0.368164
+VERTEX_SE2 838 -12.218778 -30.573267 1.234031
+VERTEX_SE2 839 -12.217846 -30.572182 1.017315
+VERTEX_SE2 840 -12.205638 -30.563033 0.457221
+VERTEX_SE2 841 -12.186893 -30.559209 -0.157128
+VERTEX_SE2 842 -11.953603 -30.647983 -0.386378
+VERTEX_SE2 843 -11.425785 -30.867365 -0.387868
+VERTEX_SE2 844 -10.836985 -31.098902 -0.394843
+VERTEX_SE2 845 -10.253132 -31.347696 -0.408511
+VERTEX_SE2 846 -9.662939 -31.589256 -0.405754
+VERTEX_SE2 847 -9.086083 -31.851482 -0.431429
+VERTEX_SE2 848 -8.940268 -31.914214 0.052760
+VERTEX_SE2 849 -8.937884 -31.910733 0.981233
+VERTEX_SE2 850 -8.846299 -31.550192 1.337597
+VERTEX_SE2 851 -8.670841 -30.931185 1.246884
+VERTEX_SE2 852 -8.462808 -30.325041 1.262739
+VERTEX_SE2 853 -8.280607 -29.742061 1.236186
+VERTEX_SE2 854 -8.076287 -29.173781 1.239399
+VERTEX_SE2 855 -7.887388 -28.592768 1.238706
+VERTEX_SE2 856 -7.661883 -27.996043 1.201622
+VERTEX_SE2 857 -7.435282 -27.400366 1.195491
+VERTEX_SE2 858 -7.181293 -26.816604 1.144746
+VERTEX_SE2 859 -6.975384 -26.352422 1.141340
+VERTEX_SE2 860 -6.975931 -26.349425 2.005134
+VERTEX_SE2 861 -7.070368 -26.315710 2.933845
+VERTEX_SE2 862 -7.703743 -26.156922 2.877954
+VERTEX_SE2 863 -8.318477 -25.984947 2.848940
+VERTEX_SE2 864 -8.894038 -25.792766 2.850044
+VERTEX_SE2 865 -9.480815 -25.646186 2.911227
+VERTEX_SE2 866 -10.042232 -25.502772 2.913209
+VERTEX_SE2 867 -10.195104 -25.469004 3.098784
+VERTEX_SE2 868 -10.213426 -25.478919 -2.146684
+VERTEX_SE2 869 -10.215119 -25.492408 -1.155028
+VERTEX_SE2 870 -10.214332 -25.494499 -0.141931
+VERTEX_SE2 871 -10.213017 -25.492991 0.844964
+VERTEX_SE2 872 -10.207635 -25.487052 1.539524
+VERTEX_SE2 873 -10.203844 -25.478644 0.974807
+VERTEX_SE2 874 -10.191816 -25.467641 0.422903
+VERTEX_SE2 875 -10.178876 -25.463448 -0.155631
+VERTEX_SE2 876 -9.623904 -25.632105 -0.308985
+VERTEX_SE2 877 -9.083899 -25.830525 -0.389894
+VERTEX_SE2 878 -8.876969 -25.899540 -0.000578
+VERTEX_SE2 879 -8.229916 -25.842173 0.054103
+VERTEX_SE2 880 -7.774580 -25.835590 -0.054479
+VERTEX_SE2 881 -7.817933 -25.833359 -0.045761
+VERTEX_SE2 882 -7.174094 -25.927843 -0.286988
+VERTEX_SE2 883 -6.578127 -26.179696 -0.472812
+VERTEX_SE2 884 -6.240032 -26.360890 -0.535840
+VERTEX_SE2 885 -6.234259 -26.360820 0.054937
+VERTEX_SE2 886 -6.226914 -26.353411 1.089009
+VERTEX_SE2 887 -6.223165 -26.344082 2.116331
+VERTEX_SE2 888 -6.228613 -26.341527 3.115899
+VERTEX_SE2 889 -6.233959 -26.343474 -2.255359
+VERTEX_SE2 890 -6.384262 -26.679298 -1.975677
+VERTEX_SE2 891 -6.638596 -27.241278 -2.042104
+VERTEX_SE2 892 -6.943864 -27.800951 -2.074085
+VERTEX_SE2 893 -7.222566 -28.381189 -1.832614
+VERTEX_SE2 894 -7.306963 -29.019629 -1.606544
+VERTEX_SE2 895 -7.223579 -29.638727 -1.302591
+VERTEX_SE2 896 -7.217764 -29.658031 -0.821107
+VERTEX_SE2 897 -6.741710 -29.937142 -0.546756
+VERTEX_SE2 898 -6.211746 -30.256253 -0.528856
+VERTEX_SE2 899 -5.784445 -30.515658 -0.593948
+VERTEX_SE2 900 -5.213641 -30.892109 -0.593973
+VERTEX_SE2 901 -4.743942 -31.232862 -0.655646
+VERTEX_SE2 902 -4.223039 -31.613559 -0.627847
+VERTEX_SE2 903 -3.820846 -31.901295 -0.669947
+VERTEX_SE2 904 -3.815849 -31.904352 0.045079
+VERTEX_SE2 905 -3.263955 -31.843907 0.103405
+VERTEX_SE2 906 -2.639473 -31.754495 0.172374
+VERTEX_SE2 907 -2.019027 -31.639234 0.167356
+VERTEX_SE2 908 -1.390615 -31.531155 0.192144
+VERTEX_SE2 909 -0.774159 -31.409648 0.174319
+VERTEX_SE2 910 -0.621113 -31.427046 -0.195369
+VERTEX_SE2 911 -0.014492 -31.535247 -0.134304
+VERTEX_SE2 912 0.586470 -31.609953 -0.123402
+VERTEX_SE2 913 1.163336 -31.678045 -0.116774
+VERTEX_SE2 914 1.788505 -31.757735 -0.141346
+VERTEX_SE2 915 2.338537 -31.842759 -0.178606
+VERTEX_SE2 916 2.533087 -31.771891 0.368065
+VERTEX_SE2 917 3.132539 -31.589985 0.113800
+VERTEX_SE2 918 3.652121 -31.566106 0.038805
+VERTEX_SE2 919 4.280972 -31.547492 -0.003530
+VERTEX_SE2 920 4.910829 -31.560372 -0.019732
+VERTEX_SE2 921 5.544993 -31.581438 -0.071106
+VERTEX_SE2 922 6.178198 -31.632867 -0.095979
+VERTEX_SE2 923 6.782469 -31.705277 -0.156454
+VERTEX_SE2 924 7.306767 -31.788672 -0.137071
+VERTEX_SE2 925 7.316981 -31.785338 0.373816
+VERTEX_SE2 926 7.870711 -31.558218 0.392795
+VERTEX_SE2 927 8.451492 -31.319547 0.372320
+VERTEX_SE2 928 9.048413 -31.086577 0.366185
+VERTEX_SE2 929 9.642832 -30.858817 0.368104
+VERTEX_SE2 930 10.245448 -30.641674 0.289261
+VERTEX_SE2 931 10.860347 -30.480136 0.213162
+VERTEX_SE2 932 11.487766 -30.354631 0.158095
+VERTEX_SE2 933 12.113942 -30.270301 0.098329
+VERTEX_SE2 934 12.615349 -30.217794 0.093110
+VERTEX_SE2 935 12.620802 -30.215724 0.789990
+VERTEX_SE2 936 12.621200 -30.213495 1.735352
+VERTEX_SE2 937 12.506666 -29.673239 1.798228
+VERTEX_SE2 938 12.424893 -29.074588 1.624736
+VERTEX_SE2 939 12.382460 -28.442898 1.652316
+VERTEX_SE2 940 12.358048 -27.806499 1.569594
+VERTEX_SE2 941 12.373922 -27.170573 1.518896
+VERTEX_SE2 942 12.403040 -26.619551 1.526103
+VERTEX_SE2 943 12.433212 -25.976160 1.617626
+VERTEX_SE2 944 12.409024 -25.337583 1.563948
+VERTEX_SE2 945 12.425512 -24.701834 1.511054
+VERTEX_SE2 946 12.438281 -24.522578 1.577626
+VERTEX_SE2 947 12.297194 -24.116617 1.909253
+VERTEX_SE2 948 12.106012 -23.569193 1.887290
+VERTEX_SE2 949 11.964410 -22.979201 1.728071
+VERTEX_SE2 950 11.889816 -22.346608 1.484552
+VERTEX_SE2 951 11.958985 -21.712798 1.409506
+VERTEX_SE2 952 12.033066 -21.078819 1.656468
+VERTEX_SE2 953 11.960841 -20.446967 1.733995
+VERTEX_SE2 954 11.870328 -19.821157 1.720988
+VERTEX_SE2 955 11.840813 -19.182342 1.553709
+VERTEX_SE2 956 11.856933 -18.549356 1.547775
+VERTEX_SE2 957 11.900583 -17.914412 1.456986
+VERTEX_SE2 958 11.980717 -17.309521 1.428422
+VERTEX_SE2 959 12.082916 -16.713544 1.360362
+VERTEX_SE2 960 12.156646 -16.109750 1.448732
+VERTEX_SE2 961 12.237458 -15.513097 1.428643
+VERTEX_SE2 962 12.263723 -14.879685 1.501648
+VERTEX_SE2 963 12.237575 -14.246674 1.697303
+VERTEX_SE2 964 12.165060 -13.610953 1.639856
+VERTEX_SE2 965 12.127557 -12.978752 1.638378
+VERTEX_SE2 966 12.104648 -12.566160 1.581231
+VERTEX_SE2 967 12.101573 -12.558682 2.440323
+VERTEX_SE2 968 12.096363 -12.554972 -2.940213
+VERTEX_SE2 969 12.095404 -12.555254 -2.878924
+VERTEX_SE2 970 12.095404 -12.555254 -2.879037
+VERTEX_SE2 971 11.746171 -12.650445 -2.877325
+VERTEX_SE2 972 11.152947 -12.816606 -2.870194
+VERTEX_SE2 973 10.545291 -12.861291 3.130276
+VERTEX_SE2 974 9.909280 -12.851322 -3.119743
+VERTEX_SE2 975 9.273543 -12.871196 -3.113968
+VERTEX_SE2 976 8.636290 -12.899229 -3.099985
+VERTEX_SE2 977 7.998434 -12.914064 -3.126289
+VERTEX_SE2 978 7.362084 -12.942484 -3.081464
+VERTEX_SE2 979 6.727323 -12.975809 -3.095884
+VERTEX_SE2 980 6.088538 -13.025797 -3.052420
+VERTEX_SE2 981 5.456362 -13.081213 -3.049818
+VERTEX_SE2 982 4.878233 -13.153816 -3.010682
+VERTEX_SE2 983 4.276746 -13.227843 -3.016388
+VERTEX_SE2 984 3.677713 -13.322859 -2.961936
+VERTEX_SE2 985 3.077590 -13.433257 -2.944700
+VERTEX_SE2 986 2.454219 -13.573733 -2.911877
+VERTEX_SE2 987 1.831643 -13.709396 -2.952510
+VERTEX_SE2 988 1.208691 -13.826413 -2.942854
+VERTEX_SE2 989 0.584787 -13.958913 -2.938610
+VERTEX_SE2 990 -0.036556 -14.080445 -2.953180
+VERTEX_SE2 991 -0.661927 -14.209275 -2.932525
+VERTEX_SE2 992 -1.260572 -14.319726 -2.969755
+VERTEX_SE2 993 -1.888936 -14.441757 -2.941917
+VERTEX_SE2 994 -2.487885 -14.558335 -2.956980
+VERTEX_SE2 995 -3.058043 -14.679439 -2.909164
+VERTEX_SE2 996 -3.642056 -14.831099 -2.881732
+VERTEX_SE2 997 -4.264284 -14.974196 -2.946069
+VERTEX_SE2 998 -4.649607 -15.053751 -2.924278
+VERTEX_SE2 999 -4.656689 -15.065859 -2.206631
+VERTEX_SE2 1000 -4.965388 -15.623496 -2.058280
+VERTEX_SE2 1001 -5.318062 -16.158055 -2.379913
+VERTEX_SE2 1002 -5.750626 -16.618291 -2.287924
+VERTEX_SE2 1003 -6.211655 -17.061941 -2.468589
+VERTEX_SE2 1004 -6.694526 -17.473495 -2.405819
+VERTEX_SE2 1005 -7.127979 -17.892536 -2.338545
+VERTEX_SE2 1006 -7.533434 -18.348428 -2.255884
+VERTEX_SE2 1007 -7.879092 -18.809574 -2.158490
+VERTEX_SE2 1008 -8.039907 -19.059004 -1.992248
+VERTEX_SE2 1009 -8.036682 -19.246221 -1.535293
+VERTEX_SE2 1010 -8.014039 -19.881169 -1.488904
+VERTEX_SE2 1011 -7.963340 -20.508886 -1.536571
+VERTEX_SE2 1012 -7.940438 -21.138959 -1.498741
+VERTEX_SE2 1013 -7.851368 -21.773013 -1.387987
+VERTEX_SE2 1014 -7.817932 -22.401411 -1.567544
+VERTEX_SE2 1015 -7.777031 -23.038795 -1.486212
+VERTEX_SE2 1016 -7.720006 -23.818187 -1.481750
+VERTEX_SE2 1017 -7.654678 -24.418258 -1.539186
+VERTEX_SE2 1018 -7.642739 -24.996103 -1.532186
+VERTEX_SE2 1019 -7.587869 -25.606880 -1.473009
+VERTEX_SE2 1020 -7.542280 -26.239004 -1.487341
+VERTEX_SE2 1021 -7.489141 -26.876264 -1.528391
+VERTEX_SE2 1022 -7.485868 -26.947021 -1.536042
+VERTEX_SE2 1023 -7.484661 -26.958141 -1.449942
+VERTEX_SE2 1024 -7.409816 -27.598995 -1.424093
+VERTEX_SE2 1025 -7.295845 -28.237813 -1.407035
+VERTEX_SE2 1026 -7.266936 -28.415848 -1.400374
+VERTEX_SE2 1027 -7.264213 -28.420001 -0.485709
+VERTEX_SE2 1028 -7.082225 -28.411802 0.076550
+VERTEX_SE2 1029 -6.501990 -28.370465 0.054524
+VERTEX_SE2 1030 -5.899285 -28.359129 -0.023135
+VERTEX_SE2 1031 -5.264812 -28.390632 -0.074570
+VERTEX_SE2 1032 -4.627186 -28.437737 -0.067955
+VERTEX_SE2 1033 -3.988448 -28.495960 -0.110249
+VERTEX_SE2 1034 -3.830826 -28.515420 -0.320119
+VERTEX_SE2 1035 -3.824146 -28.521449 -0.932344
+VERTEX_SE2 1036 -3.823513 -28.519287 -1.496421
+VERTEX_SE2 1037 -3.907010 -28.904450 -1.730668
+VERTEX_SE2 1038 -3.935283 -29.554657 -1.636155
+VERTEX_SE2 1039 -4.005708 -30.240003 -1.664719
+VERTEX_SE2 1040 -4.005908 -30.238599 -1.026894
+VERTEX_SE2 1041 -4.005975 -30.237093 0.002348
+VERTEX_SE2 1042 -3.997565 -30.235981 1.002167
+VERTEX_SE2 1043 -3.992361 -30.227413 1.983494
+VERTEX_SE2 1044 -3.977187 -30.235628 2.989203
+VERTEX_SE2 1045 -3.975026 -30.236085 2.875365
+VERTEX_SE2 1046 -3.962563 -30.241673 2.490123
+VERTEX_SE2 1047 -3.950447 -30.258328 1.934722
+VERTEX_SE2 1048 -3.961452 -29.893794 1.621975
+VERTEX_SE2 1049 -4.005576 -29.246490 1.639262
+VERTEX_SE2 1050 -4.077126 -28.603234 1.715064
+VERTEX_SE2 1051 -4.144972 -27.965909 1.641633
+VERTEX_SE2 1052 -4.202505 -27.357765 1.700204
+VERTEX_SE2 1053 -4.242648 -26.957178 1.653111
+VERTEX_SE2 1054 -4.243150 -26.953596 2.434770
+VERTEX_SE2 1055 -4.236475 -26.953142 -2.756219
+VERTEX_SE2 1056 -4.223234 -26.936933 -1.722386
+VERTEX_SE2 1057 -4.227338 -26.917941 -0.719127
+VERTEX_SE2 1058 -4.226406 -26.918299 0.214528
+VERTEX_SE2 1059 -3.650549 -26.814433 0.137155
+VERTEX_SE2 1060 -3.017058 -26.728657 0.145123
+VERTEX_SE2 1061 -2.566458 -26.676490 0.026280
+VERTEX_SE2 1062 -2.547934 -26.680711 -0.534242
+VERTEX_SE2 1063 -2.549662 -26.679283 -1.128091
+VERTEX_SE2 1064 -2.494849 -26.986675 -1.390919
+VERTEX_SE2 1065 -2.341227 -27.585706 -1.267035
+VERTEX_SE2 1066 -2.181042 -28.156133 -1.321458
+VERTEX_SE2 1067 -2.176008 -28.167308 -0.885641
+VERTEX_SE2 1068 -2.171515 -28.170280 -0.208552
+VERTEX_SE2 1069 -2.166440 -28.170156 -0.036102
+VERTEX_SE2 1070 -2.158515 -28.171216 -0.571481
+VERTEX_SE2 1071 -1.728296 -28.528563 -0.696733
+VERTEX_SE2 1072 -1.327331 -28.874102 -0.763594
+VERTEX_SE2 1073 -1.328212 -28.872089 -1.271112
+VERTEX_SE2 1074 -1.186974 -29.415680 -1.303788
+VERTEX_SE2 1075 -1.030631 -30.004733 -1.285588
+VERTEX_SE2 1076 -1.010783 -30.067165 -0.872464
+VERTEX_SE2 1077 -0.990761 -30.068841 -0.051064
+VERTEX_SE2 1078 -0.349127 -30.042537 -0.001133
+VERTEX_SE2 1079 0.251517 -30.025133 0.066104
+VERTEX_SE2 1080 0.250521 -30.025208 -0.411064
+VERTEX_SE2 1081 0.710773 -30.299114 -0.528492
+VERTEX_SE2 1082 0.906064 -30.410866 -0.239852
+VERTEX_SE2 1083 0.893124 -30.419745 0.817776
+VERTEX_SE2 1084 0.892987 -30.410710 1.808848
+VERTEX_SE2 1085 0.877326 -30.393872 2.785923
+VERTEX_SE2 1086 0.299041 -30.311718 3.014416
+VERTEX_SE2 1087 -0.304600 -30.219651 3.001192
+VERTEX_SE2 1088 -0.901080 -30.145015 2.983479
+VERTEX_SE2 1089 -0.971780 -30.133164 2.884958
+VERTEX_SE2 1090 -0.973114 -30.132686 2.263087
+VERTEX_SE2 1091 -1.258802 -29.655877 2.082828
+VERTEX_SE2 1092 -1.565146 -29.096531 2.065302
+VERTEX_SE2 1093 -1.831232 -28.571344 1.997715
+VERTEX_SE2 1094 -1.829673 -28.566075 1.590728
+VERTEX_SE2 1095 -1.822889 -28.540013 0.997280
+VERTEX_SE2 1096 -1.811806 -28.530957 0.422426
+VERTEX_SE2 1097 -1.452357 -28.453682 0.204872
+VERTEX_SE2 1098 -0.806231 -28.342284 0.146524
+VERTEX_SE2 1099 -0.207476 -28.279115 0.048016
+VERTEX_SE2 1100 -0.187763 -28.277509 0.407350
+VERTEX_SE2 1101 0.022408 -28.110407 0.670039
+VERTEX_SE2 1102 0.031962 -28.106738 0.272412
+VERTEX_SE2 1103 0.639388 -27.958876 0.236513
+VERTEX_SE2 1104 1.275605 -27.810841 0.206756
+VERTEX_SE2 1105 1.907140 -27.685723 0.186870
+VERTEX_SE2 1106 2.395193 -27.596899 0.159641
+VERTEX_SE2 1107 2.402168 -27.592873 0.412775
+VERTEX_SE2 1108 2.958139 -27.302229 0.418732
+VERTEX_SE2 1109 3.567153 -27.081855 0.312557
+VERTEX_SE2 1110 4.153225 -26.897988 0.261047
+VERTEX_SE2 1111 4.708902 -26.834648 0.157605
+VERTEX_SE2 1112 5.252614 -26.628115 0.500855
+VERTEX_SE2 1113 5.822286 -26.335525 0.403408
+VERTEX_SE2 1114 6.390291 -26.092686 0.418701
+VERTEX_SE2 1115 6.922867 -25.852780 0.400788
+VERTEX_SE2 1116 7.511667 -25.579208 0.435293
+VERTEX_SE2 1117 7.600383 -25.536976 0.305438
+VERTEX_SE2 1118 7.602610 -25.537159 -0.306056
+VERTEX_SE2 1119 7.600066 -25.535572 -0.741091
+VERTEX_SE2 1120 8.016891 -25.978082 -0.806559
+VERTEX_SE2 1121 8.158671 -26.132496 -0.927181
+VERTEX_SE2 1122 8.158918 -26.136107 -1.481463
+VERTEX_SE2 1123 8.202585 -26.722199 -1.466214
+VERTEX_SE2 1124 8.300951 -27.294198 -1.369439
+VERTEX_SE2 1125 8.427601 -27.927776 -1.357617
+VERTEX_SE2 1126 8.448389 -28.015008 -1.020843
+VERTEX_SE2 1127 8.448797 -28.014120 0.029251
+VERTEX_SE2 1128 8.446703 -28.014495 1.009931
+VERTEX_SE2 1129 8.448367 -28.002253 2.018659
+VERTEX_SE2 1130 8.179683 -27.484075 2.030704
+VERTEX_SE2 1131 8.020715 -26.725314 1.595581
+VERTEX_SE2 1132 8.007311 -26.085207 1.574275
+VERTEX_SE2 1133 8.027146 -25.500857 1.533912
+VERTEX_SE2 1134 8.037276 -25.234473 1.435052
+VERTEX_SE2 1135 8.041135 -25.225813 0.875236
+VERTEX_SE2 1136 8.045119 -25.226197 0.309468
+VERTEX_SE2 1137 8.350426 -25.173106 0.123314
+VERTEX_SE2 1138 9.001574 -25.103517 0.105516
+VERTEX_SE2 1139 9.526482 -25.047001 0.028463
+VERTEX_SE2 1140 9.524465 -25.046883 -0.458084
+VERTEX_SE2 1141 9.526460 -25.047900 -1.013894
+VERTEX_SE2 1142 9.607360 -25.436185 -1.384688
+VERTEX_SE2 1143 9.757086 -26.048918 -1.299305
+VERTEX_SE2 1144 9.911339 -26.642229 -1.333595
+VERTEX_SE2 1145 10.051242 -27.237116 -1.362737
+VERTEX_SE2 1146 10.176396 -27.833614 -1.346612
+VERTEX_SE2 1147 10.348017 -28.420420 -1.277963
+VERTEX_SE2 1148 10.522608 -29.006300 -1.265737
+VERTEX_SE2 1149 10.546607 -29.077059 -0.762568
+VERTEX_SE2 1150 10.540261 -29.074848 0.225763
+VERTEX_SE2 1151 10.553029 -29.065002 1.213625
+VERTEX_SE2 1152 10.547143 -29.052737 2.249842
+VERTEX_SE2 1153 10.539006 -29.045893 -3.036684
+VERTEX_SE2 1154 10.279724 -29.230068 -2.499597
+VERTEX_SE2 1155 9.768765 -29.605741 -2.552981
+VERTEX_SE2 1156 9.258910 -29.939074 -2.546643
+VERTEX_SE2 1157 8.791360 -30.283703 -2.440027
+VERTEX_SE2 1158 8.293580 -30.637927 -2.573320
+VERTEX_SE2 1159 7.766648 -30.929430 -2.672819
+VERTEX_SE2 1160 7.188507 -31.197997 -2.815407
+VERTEX_SE2 1161 6.565573 -31.348475 -2.910356
+VERTEX_SE2 1162 5.944969 -31.503360 -2.857013
+VERTEX_SE2 1163 5.325232 -31.686006 -2.866763
+VERTEX_SE2 1164 4.712273 -31.878415 -2.786199
+VERTEX_SE2 1165 4.215997 -32.064635 -2.806894
+VERTEX_SE2 1166 4.211816 -32.067381 -2.313330
+VERTEX_SE2 1167 4.212397 -32.068184 -1.368491
+VERTEX_SE2 1168 4.215987 -32.071852 -0.457146
+VERTEX_SE2 1169 4.277451 -32.051395 0.371897
+VERTEX_SE2 1170 4.829613 -31.826964 0.380849
+VERTEX_SE2 1171 5.421192 -31.572841 0.415111
+VERTEX_SE2 1172 5.981253 -31.335402 0.355461
+VERTEX_SE2 1173 6.575628 -31.109741 0.367274
+VERTEX_SE2 1174 7.180922 -30.893036 0.301697
+VERTEX_SE2 1175 7.792370 -30.719051 0.271366
+VERTEX_SE2 1176 8.409541 -30.550025 0.230936
+VERTEX_SE2 1177 9.024476 -30.404549 0.236005
+VERTEX_SE2 1178 9.647424 -30.266268 0.192062
+VERTEX_SE2 1179 10.265276 -30.135370 0.224605
+VERTEX_SE2 1180 10.529482 -30.074919 0.220636
+VERTEX_SE2 1181 10.535574 -30.072977 1.058820
+VERTEX_SE2 1182 10.524149 -30.016817 1.779823
+VERTEX_SE2 1183 10.386448 -29.400748 1.808327
+VERTEX_SE2 1184 10.207851 -28.783707 1.881370
+VERTEX_SE2 1185 10.025332 -28.173735 1.852352
+VERTEX_SE2 1186 9.825515 -27.568409 1.922073
+VERTEX_SE2 1187 9.605142 -26.948356 1.888299
+VERTEX_SE2 1188 9.398682 -26.350552 1.909670
+VERTEX_SE2 1189 9.199117 -25.746642 1.931343
+VERTEX_SE2 1190 9.094298 -25.467233 1.939338
+VERTEX_SE2 1191 9.094967 -25.468452 2.859515
+VERTEX_SE2 1192 9.008026 -25.506399 -2.626152
+VERTEX_SE2 1193 8.461781 -25.785098 -2.758330
+VERTEX_SE2 1194 7.923840 -26.019541 -2.716510
+VERTEX_SE2 1195 7.347445 -26.288871 -2.664510
+VERTEX_SE2 1196 6.780364 -26.579172 -2.837709
+VERTEX_SE2 1197 6.180419 -26.774947 -2.826952
+VERTEX_SE2 1198 5.583380 -27.006326 -2.569041
+VERTEX_SE2 1199 5.035569 -27.311853 -2.784743
+VERTEX_SE2 1200 4.440692 -27.555930 -2.716631
+VERTEX_SE2 1201 3.868153 -27.824566 -2.661795
+VERTEX_SE2 1202 3.307623 -28.126760 -2.639885
+VERTEX_SE2 1203 2.784459 -28.432197 -2.731103
+VERTEX_SE2 1204 2.199445 -28.603325 -2.879452
+VERTEX_SE2 1205 1.642686 -28.765416 -2.851240
+VERTEX_SE2 1206 1.070524 -28.960362 -2.791568
+VERTEX_SE2 1207 0.458097 -29.116494 -2.879433
+VERTEX_SE2 1208 -0.157073 -29.300653 -2.816562
+VERTEX_SE2 1209 -0.759388 -29.505640 -2.820223
+VERTEX_SE2 1210 -1.349503 -29.728180 -2.801535
+VERTEX_SE2 1211 -1.962101 -29.894344 -2.871965
+VERTEX_SE2 1212 -2.570554 -30.072460 -2.819915
+VERTEX_SE2 1213 -3.165262 -30.298664 -2.744821
+VERTEX_SE2 1214 -3.865282 -30.564861 -2.965631
+VERTEX_SE2 1215 -4.462533 -30.687173 -2.905497
+VERTEX_SE2 1216 -4.996128 -30.904402 -2.687065
+VERTEX_SE2 1217 -5.548071 -31.150837 -2.705863
+VERTEX_SE2 1218 -6.079683 -31.407444 -2.756532
+VERTEX_SE2 1219 -6.680544 -31.658044 -2.725934
+VERTEX_SE2 1220 -7.206328 -31.919274 -2.635196
+VERTEX_SE2 1221 -7.204948 -31.917957 -3.087949
+VERTEX_SE2 1222 -7.218143 -31.913501 2.597929
+VERTEX_SE2 1223 -7.226028 -31.904243 2.038302
+VERTEX_SE2 1224 -7.405412 -31.351278 1.855394
+VERTEX_SE2 1225 -7.584838 -30.751843 1.869158
+VERTEX_SE2 1226 -7.616041 -30.650012 1.852427
+VERTEX_SE2 1227 -7.616041 -30.650012 1.851765
+EDGE_SE2 0 1 0.000000 0.000000 -0.000642 11.111271 -0.249667 0.000000 399.999840 0.000000 2496.793089
+EDGE_SE2 1 2 0.000000 0.000000 -0.000538 11.111224 -0.209222 0.000000 399.999887 0.000000 2497.312169
+EDGE_SE2 2 3 0.011003 -0.000962 -0.002382 5898.288051 69216.359995 0.000000 813797.504789 0.000000 2488.132420
+EDGE_SE2 3 4 0.630039 -0.007981 -0.003882 11.129692 2.115033 0.000000 251.862638 0.000000 2480.702442
+EDGE_SE2 4 5 0.055010 -0.000106 -0.091282 274.195567 -2936.281177 0.000000 32782.895793 0.000000 2099.259006
+EDGE_SE2 5 6 0.004599 -0.003282 -0.797272 97512.798743 -544001.571431 0.000000 3035217.135802 0.000000 773.949086
+EDGE_SE2 6 7 -0.019286 0.007346 -0.615537 14562.788488 -56611.041711 0.000000 220247.580117 0.000000 957.869160
+EDGE_SE2 7 8 -0.022127 0.006629 -0.613534 18833.046432 -56332.014355 0.000000 168606.730383 0.000000 960.248785
+EDGE_SE2 8 9 -0.021138 0.006734 -0.638070 21300.350989 -62226.140556 0.000000 181891.375069 0.000000 931.697855
+EDGE_SE2 9 10 -0.012731 0.002805 -0.614531 88261.230144 -210099.692864 0.000000 500201.721901 0.000000 959.062847
+EDGE_SE2 10 11 -0.004733 0.001621 -0.674279 455441.532335 -1269769.465818 0.000000 3540210.494348 0.000000 891.834664
+EDGE_SE2 11 12 0.000807 -0.000605 -0.649474 3209.969094 -560838.218926 0.000000 98328698.890567 0.000000 918.859395
+EDGE_SE2 12 13 0.017463 -0.005758 -0.659498 33087.416467 -93212.317327 0.000000 262692.689594 0.000000 907.792399
+EDGE_SE2 13 14 0.024327 -0.007794 -0.608239 13237.887356 -43033.186144 0.000000 140019.158071 0.000000 966.582281
+EDGE_SE2 14 15 0.008665 -0.002176 -0.524928 94975.828833 -331589.466697 0.000000 1157826.108740 0.000000 1075.081358
+EDGE_SE2 15 16 0.300013 0.002659 -0.018692 11.945981 -30.290393 0.000000 1110.094393 0.000000 2409.096616
+EDGE_SE2 16 17 0.618894 -0.006590 -0.031228 11.216951 -5.142163 0.000000 260.940781 0.000000 2350.880836
+EDGE_SE2 17 18 0.644399 0.002908 -0.010177 11.160679 -3.373944 0.000000 240.764207 0.000000 2449.881377
+EDGE_SE2 18 19 0.657345 -0.022632 -0.048576 11.155234 -3.115574 0.000000 231.108306 0.000000 2273.736754
+EDGE_SE2 19 20 0.644638 0.002939 0.010643 11.119605 1.396220 0.000000 240.626947 0.000000 2447.622654
+EDGE_SE2 20 21 0.643768 0.040732 0.117695 11.791489 12.469629 0.000000 239.648403 0.000000 2001.213355
+EDGE_SE2 21 22 0.641586 -0.019837 0.022682 11.775592 12.387374 0.000000 242.038634 0.000000 2390.335076
+EDGE_SE2 22 23 0.642142 0.071066 0.114072 11.114499 0.879730 0.000000 239.576730 0.000000 2014.250547
+EDGE_SE2 23 24 0.642775 -0.026027 -0.050939 11.136380 -2.413434 0.000000 241.616002 0.000000 2263.523413
+EDGE_SE2 24 25 0.645593 0.014612 0.008602 11.156105 -3.207460 0.000000 239.760661 0.000000 2457.538661
+EDGE_SE2 25 26 0.612608 -0.020554 -0.040332 11.122880 -1.732513 0.000000 266.150269 0.000000 2309.915505
+EDGE_SE2 26 27 0.617908 0.014448 0.016074 11.124480 -1.830524 0.000000 261.753630 0.000000 2421.527089
+EDGE_SE2 27 28 0.585700 -0.007698 -0.004161 11.133727 2.517886 0.000000 291.434633 0.000000 2479.324138
+EDGE_SE2 28 29 0.378831 0.003536 0.031104 11.435983 14.920983 0.000000 696.414325 0.000000 2351.446301
+EDGE_SE2 29 30 0.007031 -0.000919 -0.531386 303620.480641 -715329.968352 0.000000 1685390.466875 0.000000 1066.033037
+EDGE_SE2 30 31 0.172814 -0.047579 -0.267833 11.113242 2.570601 0.000000 3112.523002 0.000000 1555.306207
+EDGE_SE2 31 32 0.643089 -0.013458 -0.018151 11.112884 0.639397 0.000000 241.693017 0.000000 2411.657469
+EDGE_SE2 32 33 0.641505 0.012210 0.053138 11.380647 7.899680 0.000000 242.638725 0.000000 2254.080602
+EDGE_SE2 33 34 0.642958 0.012818 0.023470 11.113996 0.815809 0.000000 241.800271 0.000000 2386.655713
+EDGE_SE2 34 35 0.642138 0.012026 0.036992 11.188281 4.224347 0.000000 242.355561 0.000000 2324.819270
+EDGE_SE2 35 36 0.646989 -0.005904 -0.005774 11.113668 0.763126 0.000000 238.872355 0.000000 2471.378132
+EDGE_SE2 36 37 0.422413 0.003265 0.010657 11.115820 1.608217 0.000000 560.397185 0.000000 2447.554843
+EDGE_SE2 37 38 0.004147 -0.000362 -0.316561 298816.394178 -1278713.788579 0.000000 5472166.543975 0.000000 1442.308081
+EDGE_SE2 38 39 0.031682 -0.005795 -0.166903 29.991712 1348.903464 0.000000 96382.012864 0.000000 1835.990780
+EDGE_SE2 39 40 0.628745 0.004932 0.020565 11.150244 3.076040 0.000000 252.904983 0.000000 2400.262103
+EDGE_SE2 40 41 0.654706 -0.007135 -0.028394 11.179108 -3.886059 0.000000 233.200483 0.000000 2363.855583
+EDGE_SE2 41 42 0.615233 -0.005892 -0.018963 11.133406 -2.375163 0.000000 264.145862 0.000000 2407.815356
+EDGE_SE2 42 43 0.646018 -0.015551 -0.036078 11.144050 -2.742429 0.000000 239.441473 0.000000 2328.922864
+EDGE_SE2 43 44 0.644889 -0.007273 -0.032646 11.215795 -4.898393 0.000000 240.317651 0.000000 2344.428944
+EDGE_SE2 44 45 0.642617 -0.019475 -0.055423 11.256800 -5.797160 0.000000 241.788650 0.000000 2244.330959
+EDGE_SE2 45 46 0.643577 -0.008674 -0.019276 11.118853 -1.335200 0.000000 241.382966 0.000000 2406.336795
+EDGE_SE2 46 47 0.643124 -0.007411 -0.041538 11.318826 -6.918261 0.000000 241.534792 0.000000 2304.569286
+EDGE_SE2 47 48 0.647528 -0.005000 -0.006399 11.111509 0.300792 0.000000 238.482697 0.000000 2468.309505
+EDGE_SE2 48 49 0.643552 -0.004657 -0.050649 11.544947 -9.986829 0.000000 241.006497 0.000000 2264.773140
+EDGE_SE2 49 50 0.613650 -0.021431 -0.044298 11.133509 -2.385631 0.000000 265.211665 0.000000 2292.403781
+EDGE_SE2 50 51 0.614419 0.001282 -0.030028 11.372766 -8.144597 0.000000 264.630129 0.000000 2356.361658
+EDGE_SE2 51 52 0.612275 -0.025515 -0.077517 11.439261 -9.144885 0.000000 265.960759 0.000000 2153.236570
+EDGE_SE2 52 53 0.589010 0.013532 0.011867 11.145260 -3.075254 0.000000 288.053971 0.000000 2441.704725
+EDGE_SE2 53 54 0.549942 -0.015900 -0.062397 11.469128 -10.685144 0.000000 330.013480 0.000000 2214.962293
+EDGE_SE2 54 55 -0.007990 -0.000400 0.004985 3173.514815 -70220.700546 0.000000 1559251.248529 0.000000 2475.260146
+EDGE_SE2 55 56 0.031075 -0.000065 0.010280 26.926592 1279.597558 0.000000 103540.680562 0.000000 2449.381862
+EDGE_SE2 56 57 0.661651 0.003067 -0.011448 11.167314 -3.494319 0.000000 228.362912 0.000000 2443.728134
+EDGE_SE2 57 58 0.651514 0.005099 0.046426 11.445370 8.655456 0.000000 235.239298 0.000000 2283.089649
+EDGE_SE2 58 59 0.644894 -0.007287 -0.023143 11.143280 -2.715787 0.000000 240.386652 0.000000 2388.181524
+EDGE_SE2 59 60 0.641666 0.006484 0.022061 11.144235 2.770355 0.000000 242.816230 0.000000 2393.240674
+EDGE_SE2 60 61 0.644092 -0.013088 -0.049766 11.310377 -6.764558 0.000000 240.749901 0.000000 2268.584724
+EDGE_SE2 61 62 0.610542 0.010202 0.039027 11.239154 5.735944 0.000000 268.065336 0.000000 2315.721577
+EDGE_SE2 62 63 0.615687 -0.014578 -0.037143 11.156928 -3.401279 0.000000 263.609811 0.000000 2324.142368
+EDGE_SE2 63 64 0.614457 0.023223 0.060765 11.244984 5.822514 0.000000 264.348682 0.000000 2221.783030
+EDGE_SE2 64 65 0.613126 -0.015622 -0.054905 11.331684 -7.492495 0.000000 265.618387 0.000000 2246.535610
+EDGE_SE2 65 66 0.642083 0.005221 -0.012134 11.206140 -4.688688 0.000000 242.448428 0.000000 2440.416656
+EDGE_SE2 66 67 0.644032 -0.000439 -0.003525 11.112971 -0.654045 0.000000 241.091541 0.000000 2482.467756
+EDGE_SE2 67 68 0.480969 0.003132 -0.018150 11.367193 -10.381901 0.000000 432.006963 0.000000 2411.662206
+EDGE_SE2 68 69 0.010004 -0.000372 -0.158022 14522.704416 -119457.061100 0.000000 983362.087562 0.000000 1864.259601
+EDGE_SE2 69 70 0.007781 -0.000530 -0.680912 544035.164858 -773651.719241 0.000000 1100214.270443 0.000000 884.810063
+EDGE_SE2 70 71 -0.005768 0.002595 -0.648935 125743.539339 -546312.647396 0.000000 2373762.361377 0.000000 919.460202
+EDGE_SE2 71 72 0.000000 0.000000 -0.011790 11.165166 -4.584575 0.000000 399.945945 0.000000 2442.076380
+EDGE_SE2 72 73 0.003590 -0.000252 -0.067514 59.238767 19279.280557 0.000000 7723027.108236 0.000000 2193.777612
+EDGE_SE2 73 74 0.003377 -0.001263 -0.627884 547328.125180 -1977782.419372 0.000000 7146917.196299 0.000000 943.393977
+EDGE_SE2 74 75 0.001263 0.000666 -0.356531 27289611.550657 -24363663.505902 0.000000 21751450.848890 0.000000 1358.565441
+EDGE_SE2 75 76 0.014525 0.005731 0.687334 38537.927166 119650.043523 0.000000 371599.899935 0.000000 878.087699
+EDGE_SE2 76 77 0.012722 0.001600 0.229532 6624.040036 63075.527086 0.000000 601638.946912 0.000000 1653.713745
+EDGE_SE2 77 78 0.282617 0.095127 0.333053 11.189119 9.319517 0.000000 1124.510027 0.000000 1406.840866
+EDGE_SE2 78 79 0.636095 0.008032 -0.007625 11.207888 -4.778031 0.000000 247.011069 0.000000 2462.306663
+EDGE_SE2 79 80 0.646911 -0.030410 -0.077284 11.319895 -6.885926 0.000000 238.216160 0.000000 2154.168095
+EDGE_SE2 80 81 0.639697 -0.008063 -0.028569 11.170556 -3.722959 0.000000 244.273973 0.000000 2363.051282
+EDGE_SE2 81 82 0.643152 -0.022848 -0.050289 11.161415 -3.403565 0.000000 241.398318 0.000000 2266.325966
+EDGE_SE2 82 83 0.640259 -0.000745 -0.019030 11.185422 -4.158907 0.000000 243.868413 0.000000 2407.498744
+EDGE_SE2 83 84 0.642213 -0.028725 -0.071607 11.278239 -6.209353 0.000000 241.809620 0.000000 2177.051366
+EDGE_SE2 84 85 0.642807 -0.004171 0.013937 11.207431 4.714878 0.000000 241.906303 0.000000 2431.743719
+EDGE_SE2 85 86 0.729089 -0.020666 -0.079989 11.582543 -9.118938 0.000000 187.499441 0.000000 2143.389493
+EDGE_SE2 86 87 0.611674 -0.018501 -0.038112 11.126983 -2.015351 0.000000 267.015944 0.000000 2319.805566
+EDGE_SE2 87 88 0.363613 -0.001497 -0.025112 11.439512 -15.640496 0.000000 756.007915 0.000000 2379.016060
+EDGE_SE2 88 89 0.022194 0.007878 0.405075 748.400424 11505.714792 0.000000 179562.707200 0.000000 1266.312242
+EDGE_SE2 89 90 0.645333 -0.002553 -0.026790 11.230485 -5.227171 0.000000 239.999401 0.000000 2371.246746
+EDGE_SE2 90 91 0.653796 0.009633 0.053106 11.438992 8.540445 0.000000 233.567599 0.000000 2254.217590
+EDGE_SE2 91 92 0.637138 -0.022076 -0.111746 12.505303 -18.044302 0.000000 244.649107 0.000000 2022.687812
+EDGE_SE2 92 93 0.640542 -0.048819 -0.097619 11.218480 -4.981269 0.000000 242.212560 0.000000 2075.089230
+EDGE_SE2 93 94 0.639915 -0.019948 -0.040363 11.130823 -2.142336 0.000000 243.948392 0.000000 2309.777849
+EDGE_SE2 94 95 0.643361 0.058181 0.138081 11.634914 10.928304 0.000000 239.112551 0.000000 1930.161562
+EDGE_SE2 95 96 0.638452 0.002717 0.020015 11.169275 3.690420 0.000000 245.262988 0.000000 2402.851280
+EDGE_SE2 96 97 0.615807 -0.026362 -0.075608 11.382661 -8.269572 0.000000 262.946629 0.000000 2160.886525
+EDGE_SE2 97 98 0.610633 -0.021924 -0.063326 11.304343 -7.040699 0.000000 267.649507 0.000000 2211.093675
+EDGE_SE2 98 99 0.729556 0.014258 0.041080 11.193076 3.804772 0.000000 187.727053 0.000000 2306.597420
+EDGE_SE2 99 100 0.585696 -0.025742 -0.058133 11.167610 -3.975845 0.000000 290.892636 0.000000 2232.849702
+EDGE_SE2 100 101 0.637186 0.067759 0.095665 11.135663 -2.388768 0.000000 243.522972 0.000000 2082.497224
+EDGE_SE2 101 102 0.646556 -0.024441 -0.094339 11.838827 -12.853666 0.000000 238.145742 0.000000 2087.546965
+EDGE_SE2 102 103 0.640410 0.007435 0.107121 13.227361 22.089363 0.000000 241.679335 0.000000 2039.622675
+EDGE_SE2 103 104 0.644201 -0.014336 -0.024966 11.112805 -0.623830 0.000000 240.845479 0.000000 2379.693860
+EDGE_SE2 104 105 0.644960 0.019675 0.055427 11.253454 5.708380 0.000000 240.033921 0.000000 2244.313947
+EDGE_SE2 105 106 0.633327 -0.017685 -0.046638 11.194517 -4.454694 0.000000 249.035067 0.000000 2282.164848
+EDGE_SE2 106 107 0.647889 -0.007117 0.003228 11.156976 3.226972 0.000000 238.156676 0.000000 2483.937815
+EDGE_SE2 107 108 0.418841 0.012880 0.059022 11.557560 15.782621 0.000000 569.050200 0.000000 2229.102528
+EDGE_SE2 108 109 0.012870 -0.002240 -0.453333 45067.256701 -156114.787673 0.000000 540932.368601 0.000000 1183.612533
+EDGE_SE2 109 110 0.014179 -0.004043 -0.597121 45347.441263 -137112.106751 0.000000 414683.621097 0.000000 980.086413
+EDGE_SE2 110 111 0.096952 -0.046958 -0.510989 42.005133 -514.703903 0.000000 8586.236292 0.000000 1095.008280
+EDGE_SE2 111 112 0.662640 0.007778 0.052084 11.463505 8.729519 0.000000 227.358980 0.000000 2258.599235
+EDGE_SE2 112 113 0.647895 0.015723 0.044858 11.207376 4.673389 0.000000 237.990065 0.000000 2289.947176
+EDGE_SE2 113 114 0.639175 0.001049 0.034783 11.367673 7.738365 0.000000 244.514402 0.000000 2334.755667
+EDGE_SE2 114 115 0.643430 0.022360 0.055827 11.213458 4.852193 0.000000 241.150882 0.000000 2242.613753
+EDGE_SE2 115 116 0.763396 0.014434 0.039419 11.178609 3.289916 0.000000 171.464543 0.000000 2313.975233
+EDGE_SE2 116 117 0.634411 0.022615 0.090058 11.812568 12.875464 0.000000 247.444399 0.000000 2103.976068
+EDGE_SE2 117 118 0.031050 -0.001921 -0.343244 7981.193322 -27566.715976 0.000000 95358.161435 0.000000 1385.575483
+EDGE_SE2 118 119 0.498463 -0.026118 -0.058682 11.126767 -2.471741 0.000000 401.352854 0.000000 2230.534528
+EDGE_SE2 119 120 0.638636 0.019165 0.084147 11.796072 12.637674 0.000000 244.278828 0.000000 2126.981262
+EDGE_SE2 120 121 0.608883 0.022686 0.061480 11.262812 6.257264 0.000000 269.206349 0.000000 2218.790906
+EDGE_SE2 121 122 0.610979 0.006491 0.049908 11.507132 10.075663 0.000000 267.458443 0.000000 2267.971114
+EDGE_SE2 122 123 0.214919 0.006655 -0.018770 16.427458 -106.823784 0.000000 2157.570163 0.000000 2408.727735
+EDGE_SE2 123 124 0.224600 -0.105868 -0.436366 11.138335 6.622207 0.000000 1621.948711 0.000000 1211.740925
+EDGE_SE2 124 125 0.625260 -0.011376 -0.017225 11.111340 0.236437 0.000000 255.702505 0.000000 2416.050226
+EDGE_SE2 125 126 0.630905 0.083897 0.196975 12.098786 15.227356 0.000000 245.877115 0.000000 1744.897213
+EDGE_SE2 126 127 0.635911 -0.003633 -0.003082 11.112746 0.621349 0.000000 247.280806 0.000000 2484.660949
+EDGE_SE2 127 128 0.644637 0.020444 0.034153 11.112488 0.561814 0.000000 240.398060 0.000000 2337.601172
+EDGE_SE2 128 129 0.638546 -0.014303 -0.035619 11.152032 -3.094288 0.000000 245.089747 0.000000 2330.987741
+EDGE_SE2 129 130 0.640721 0.025473 0.048893 11.130575 2.125338 0.000000 243.187509 0.000000 2272.362609
+EDGE_SE2 130 131 0.641480 0.013548 0.083601 12.014929 14.445918 0.000000 242.003477 0.000000 2129.125269
+EDGE_SE2 131 132 0.641305 -0.014532 -0.055040 11.354232 -7.504896 0.000000 242.779959 0.000000 2245.960726
+EDGE_SE2 132 133 0.581934 -0.015905 -0.042094 11.173057 -4.193601 0.000000 295.010721 0.000000 2302.110777
+EDGE_SE2 133 134 0.610231 0.001805 -0.024124 11.299860 -6.968043 0.000000 268.350792 0.000000 2383.608476
+EDGE_SE2 134 135 0.579655 -0.017960 -0.033069 11.112368 -0.599782 0.000000 297.332685 0.000000 2342.509439
+EDGE_SE2 135 136 0.642725 0.014632 0.012040 11.137646 -2.474784 0.000000 241.922944 0.000000 2440.870018
+EDGE_SE2 136 137 0.634138 -0.020053 -0.051400 11.204026 -4.694831 0.000000 248.333522 0.000000 2261.538905
+EDGE_SE2 137 138 0.640742 0.028547 0.068532 11.244796 5.567274 0.000000 242.959321 0.000000 2189.600800
+EDGE_SE2 138 139 0.624343 0.022436 0.065016 11.318542 7.127247 0.000000 256.001043 0.000000 2204.081980
+EDGE_SE2 139 140 0.649355 0.026111 0.030256 11.133375 -2.241330 0.000000 236.751877 0.000000 2355.318828
+EDGE_SE2 140 141 0.633752 -0.015337 -0.048721 11.254069 -5.827843 0.000000 248.689278 0.000000 2273.108048
+EDGE_SE2 141 142 0.643523 0.009872 -0.004100 11.198132 -4.475923 0.000000 241.330701 0.000000 2479.625389
+EDGE_SE2 142 143 0.634003 -0.068517 -0.110892 11.113575 -0.760641 0.000000 245.906731 0.000000 2025.798896
+EDGE_SE2 143 144 0.367489 0.008323 0.017249 11.132342 -3.934021 0.000000 740.076637 0.000000 2415.936223
+EDGE_SE2 144 145 0.011506 -0.002421 -0.499034 59809.374609 -199183.039696 0.000000 663473.241646 0.000000 1112.543606
+EDGE_SE2 145 146 0.002065 0.000912 -0.593946 14068785.759218 -8838843.642003 0.000000 5553100.053245 0.000000 983.994793
+EDGE_SE2 146 147 0.052046 -0.024279 -0.487148 88.850566 -1532.993200 0.000000 30241.168070 0.000000 1130.398639
+EDGE_SE2 147 148 0.437634 -0.008022 -0.035943 11.269607 -8.996749 0.000000 521.795770 0.000000 2329.529896
+EDGE_SE2 148 149 0.649282 0.006558 0.024834 11.160187 3.330542 0.000000 237.137078 0.000000 2380.306915
+EDGE_SE2 149 150 0.638778 0.018547 0.013910 11.164529 -3.533262 0.000000 244.815913 0.000000 2431.874707
+EDGE_SE2 150 151 0.642396 0.027197 0.085399 11.539278 9.931167 0.000000 241.460866 0.000000 2122.077176
+EDGE_SE2 151 152 0.642196 -0.014560 -0.068180 11.589745 -10.509493 0.000000 241.870955 0.000000 2191.044127
+EDGE_SE2 152 153 0.641634 0.027219 0.085722 11.545124 10.011045 0.000000 242.028095 0.000000 2120.814737
+EDGE_SE2 153 154 0.638389 -0.020707 -0.077238 11.580742 -10.472604 0.000000 244.646718 0.000000 2154.352072
+EDGE_SE2 154 155 0.642162 0.011168 0.026427 11.130001 2.090263 0.000000 242.407116 0.000000 2372.924244
+EDGE_SE2 155 156 0.644865 0.009414 0.023665 11.129963 2.079071 0.000000 240.400517 0.000000 2385.746522
+EDGE_SE2 156 157 0.581283 -0.014428 -0.072363 11.754151 -13.514232 0.000000 295.128631 0.000000 2173.984116
+EDGE_SE2 157 158 0.187127 -0.000419 0.029090 13.902620 89.068131 0.000000 2852.990445 0.000000 2360.659192
+EDGE_SE2 158 159 -0.002775 0.000752 0.993417 10949150.533757 3540503.247990 0.000000 1144864.853964 0.000000 629.134778
+EDGE_SE2 159 160 0.010178 0.000761 1.042069 650920.894971 448555.873968 0.000000 309120.571532 0.000000 599.513799
+EDGE_SE2 160 161 -0.000005 0.000004 0.981942 2693538350855.096191 -157146640359.091309 0.000000 9168262482.076782 0.000000 636.440966
+EDGE_SE2 161 162 -0.015739 -0.012123 1.042202 35897.561333 88343.035344 0.000000 217488.511233 0.000000 599.435534
+EDGE_SE2 162 163 0.001603 0.001566 1.003233 1029828.017450 4408843.295789 0.000000 18875113.167768 0.000000 622.984264
+EDGE_SE2 163 164 0.014062 0.009080 0.929958 43510.337182 116762.574144 0.000000 313430.450998 0.000000 671.188169
+EDGE_SE2 164 165 0.127064 0.050581 0.402133 14.003612 124.194925 0.000000 5343.652150 0.000000 1271.632407
+EDGE_SE2 165 166 0.660048 0.003938 -0.000969 11.121614 -1.514549 0.000000 229.516161 0.000000 2495.162033
+EDGE_SE2 166 167 0.637952 -0.005107 -0.029173 11.216206 -4.964111 0.000000 245.589760 0.000000 2360.278446
+EDGE_SE2 167 168 0.609195 0.011564 0.012037 11.123559 -1.792903 0.000000 269.346120 0.000000 2440.884489
+EDGE_SE2 168 169 0.616410 -0.017912 -0.037053 11.127238 -2.015259 0.000000 262.946448 0.000000 2324.545784
+EDGE_SE2 169 170 0.607779 0.006983 -0.020916 11.383588 -8.405441 0.000000 270.404841 0.000000 2398.611924
+EDGE_SE2 170 171 0.584191 -0.014911 -0.038741 11.160361 -3.724488 0.000000 292.775082 0.000000 2316.996943
+EDGE_SE2 171 172 0.648836 0.010594 0.013474 11.112953 -0.645665 0.000000 237.471401 0.000000 2433.967559
+EDGE_SE2 172 173 0.642894 -0.013166 -0.018042 11.112478 0.561628 0.000000 241.844714 0.000000 2412.173920
+EDGE_SE2 173 174 0.638185 0.007116 0.045162 11.382152 7.965912 0.000000 245.229896 0.000000 2288.615243
+EDGE_SE2 174 175 0.625733 0.004082 -0.019946 11.282223 -6.462935 0.000000 255.218243 0.000000 2403.176400
+EDGE_SE2 175 176 0.613713 -0.013173 0.014287 11.435899 9.081745 0.000000 265.055874 0.000000 2430.067237
+EDGE_SE2 176 177 0.634525 0.002256 -0.022912 11.277271 -6.276557 0.000000 248.202540 0.000000 2389.260272
+EDGE_SE2 177 178 0.640137 -0.023037 -0.034183 11.111855 0.416076 0.000000 243.719928 0.000000 2337.465554
+EDGE_SE2 178 179 0.353790 0.008069 0.053221 11.839402 23.935910 0.000000 797.785636 0.000000 2253.725346
+EDGE_SE2 179 180 0.003152 -0.000263 -0.442165 1233046.693540 -3286666.439106 0.000000 8760647.410566 0.000000 1202.015605
+EDGE_SE2 180 181 0.557570 -0.008188 -0.051388 11.529199 -11.385701 0.000000 321.175409 0.000000 2261.590530
+EDGE_SE2 181 182 0.573085 -0.036151 -0.172968 14.630195 -31.871096 0.000000 299.756322 0.000000 1817.053357
+EDGE_SE2 182 183 0.603594 -0.027970 -0.056017 11.135892 -2.551709 0.000000 273.866587 0.000000 2241.806837
+EDGE_SE2 183 184 0.635433 -0.054532 -0.150813 12.107735 -15.262873 0.000000 244.855650 0.000000 1887.689196
+EDGE_SE2 184 185 0.634881 -0.022979 -0.096285 11.965079 -14.190439 0.000000 246.914669 0.000000 2080.142393
+EDGE_SE2 185 186 0.643298 -0.040128 -0.069768 11.123925 -1.715150 0.000000 240.694352 0.000000 2184.544034
+EDGE_SE2 186 187 0.616544 -0.013175 -0.025584 11.115593 -1.062453 0.000000 262.945790 0.000000 2376.826796
+EDGE_SE2 187 188 0.637286 0.000267 -0.008123 11.128264 -2.008140 0.000000 246.207666 0.000000 2459.874568
+EDGE_SE2 188 189 0.639354 -0.005159 -0.029399 11.217330 -4.979110 0.000000 244.512278 0.000000 2359.242182
+EDGE_SE2 189 190 0.641605 -0.016631 -0.026189 11.111129 -0.063557 0.000000 242.757543 0.000000 2374.025058
+EDGE_SE2 190 191 0.641101 -0.008160 -0.020962 11.126855 -1.911760 0.000000 243.247747 0.000000 2398.395787
+EDGE_SE2 191 192 0.634787 -0.009757 -0.024655 11.131543 -2.200448 0.000000 248.088013 0.000000 2381.138634
+EDGE_SE2 192 193 0.586234 -0.010454 -0.051260 11.423659 -9.345831 0.000000 290.571036 0.000000 2262.141300
+EDGE_SE2 193 194 0.611583 -0.006689 -0.021980 11.142360 -2.829372 0.000000 267.292453 0.000000 2393.620056
+EDGE_SE2 194 195 0.610567 -0.010284 -0.023227 11.121593 -1.641455 0.000000 268.159748 0.000000 2387.789433
+EDGE_SE2 195 196 0.641859 -0.011003 -0.041852 11.252480 -5.719563 0.000000 242.515471 0.000000 2303.180363
+EDGE_SE2 196 197 0.640092 -0.013813 -0.028233 11.121429 -1.549936 0.000000 243.946727 0.000000 2364.595903
+EDGE_SE2 197 198 0.639039 -0.009178 -0.058660 11.569437 -10.339579 0.000000 244.366482 0.000000 2230.627234
+EDGE_SE2 198 199 0.637088 -0.027408 -0.061598 11.192373 -4.367444 0.000000 245.840841 0.000000 2218.297682
+EDGE_SE2 199 200 0.636910 -0.008520 -0.021764 11.127669 -1.974000 0.000000 246.454469 0.000000 2394.632181
+EDGE_SE2 200 201 0.639616 -0.019900 -0.056243 11.258405 -5.857515 0.000000 244.050370 0.000000 2240.847600
+EDGE_SE2 201 202 0.573162 0.008125 0.017141 11.113691 0.869688 0.000000 304.336907 0.000000 2416.449299
+EDGE_SE2 202 203 0.807715 -0.017801 -0.055477 11.269967 -4.748397 0.000000 153.046283 0.000000 2244.101317
+EDGE_SE2 203 204 0.600516 -0.019464 -0.097088 12.222178 -17.152147 0.000000 275.898243 0.000000 2077.098438
+EDGE_SE2 204 205 0.607570 -0.009135 -0.005030 11.137105 2.598215 0.000000 270.811426 0.000000 2475.038492
+EDGE_SE2 205 206 0.587179 0.007336 0.006623 11.120721 -1.637028 0.000000 289.985432 0.000000 2467.211100
+EDGE_SE2 206 207 0.607993 0.006080 0.021126 11.143219 2.885684 0.000000 270.462940 0.000000 2397.625450
+EDGE_SE2 207 208 0.644034 -0.008545 -0.004095 11.130455 2.108903 0.000000 241.029670 0.000000 2479.650084
+EDGE_SE2 208 209 0.640840 0.009001 0.044393 11.325040 7.046915 0.000000 243.239179 0.000000 2291.986757
+EDGE_SE2 209 210 0.641153 -0.014043 -0.012923 11.129806 2.082671 0.000000 243.128297 0.000000 2436.616291
+EDGE_SE2 210 211 0.640990 0.006728 -0.001668 11.145470 -2.824640 0.000000 243.325777 0.000000 2491.680820
+EDGE_SE2 211 212 0.638573 -0.025254 -0.057210 11.184192 -4.132365 0.000000 244.776704 0.000000 2236.750195
+EDGE_SE2 212 213 0.648396 -0.008808 -0.024826 11.139763 -2.548475 0.000000 237.786398 0.000000 2380.344078
+EDGE_SE2 213 214 0.637242 -0.004643 -0.007684 11.111148 -0.093735 0.000000 246.245036 0.000000 2462.018335
+EDGE_SE2 214 215 0.369747 -0.004429 -0.039914 11.673090 -20.110851 0.000000 730.793592 0.000000 2311.772848
+EDGE_SE2 215 216 0.006980 -0.001179 -0.507763 222524.090867 -628114.036197 0.000000 1773063.824260 0.000000 1099.699039
+EDGE_SE2 216 217 -0.001832 0.001260 -0.551814 52174.391125 1025898.356469 0.000000 20176415.615022 0.000000 1038.151360
+EDGE_SE2 217 218 0.000862 -0.000506 -0.060277 20602967.870958 40459206.697150 0.000000 79452073.533188 0.000000 2223.828683
+EDGE_SE2 218 219 0.576874 -0.106568 -0.173874 11.132755 2.459345 0.000000 290.557594 0.000000 1814.249623
+EDGE_SE2 219 220 0.629125 -0.005523 -0.044144 11.413053 -8.534327 0.000000 252.332357 0.000000 2293.080041
+EDGE_SE2 220 221 0.642903 0.008921 0.051755 11.442103 8.733716 0.000000 241.563444 0.000000 2260.012484
+EDGE_SE2 221 222 0.635198 -0.000697 -0.024981 11.246132 -5.652071 0.000000 247.710771 0.000000 2379.624210
+EDGE_SE2 222 223 0.639045 0.029371 0.096256 11.701399 11.718901 0.000000 243.764798 0.000000 2080.252449
+EDGE_SE2 223 224 0.637940 -0.001297 -0.026485 11.251362 -5.734476 0.000000 245.578734 0.000000 2372.656095
+EDGE_SE2 224 225 0.639421 0.008657 0.048309 11.393218 8.109986 0.000000 244.256072 0.000000 2274.895125
+EDGE_SE2 225 226 0.638048 -0.023812 -0.051167 11.156122 -3.246372 0.000000 245.250378 0.000000 2262.541595
+EDGE_SE2 226 227 0.642744 0.047412 0.156718 12.692747 18.992206 0.000000 239.168545 0.000000 1868.465232
+EDGE_SE2 227 228 0.588969 -0.135551 -0.358747 15.698176 -34.406864 0.000000 269.191657 0.000000 1354.137035
+EDGE_SE2 228 229 0.605993 0.034684 0.124928 12.304340 17.583695 0.000000 270.228487 0.000000 1975.560427
+EDGE_SE2 229 230 0.370582 0.002463 -0.025443 11.849164 -22.992568 0.000000 727.398994 0.000000 2377.480475
+EDGE_SE2 230 231 -0.130796 -0.004868 0.073003 18.577316 208.431226 0.000000 5829.807352 0.000000 2171.391514
+EDGE_SE2 231 232 0.345343 -0.135465 -0.413759 12.252120 -28.551107 0.000000 725.536788 0.000000 1250.803404
+EDGE_SE2 232 233 0.649941 0.026872 0.109205 12.147339 15.241388 0.000000 235.289518 0.000000 2031.965694
+EDGE_SE2 233 234 0.647791 -0.001996 -0.038195 11.391127 -7.971100 0.000000 238.021188 0.000000 2319.434660
+EDGE_SE2 234 235 0.300180 0.002544 0.000515 11.180724 -8.744740 0.000000 1109.628316 0.000000 2497.426988
+EDGE_SE2 235 236 0.331863 0.149674 0.417637 11.138398 -4.503817 0.000000 754.488686 0.000000 1243.969525
+EDGE_SE2 236 237 0.654682 0.025212 0.076902 11.438281 8.513385 0.000000 232.640473 0.000000 2155.696624
+EDGE_SE2 237 238 0.648140 0.014417 -0.026834 11.656908 -11.112994 0.000000 237.383264 0.000000 2371.043534
+EDGE_SE2 238 239 0.643519 -0.017811 -0.061244 11.370468 -7.722173 0.000000 241.033805 0.000000 2219.777847
+EDGE_SE2 239 240 0.603843 -0.096900 -0.209505 11.761203 -12.890609 0.000000 266.717846 0.000000 1708.931569
+EDGE_SE2 240 241 0.584456 0.014283 0.092258 12.403890 19.031519 0.000000 291.281847 0.000000 2095.509047
+EDGE_SE2 241 242 0.612687 0.022692 0.027357 11.134913 -2.463133 0.000000 266.004463 0.000000 2368.630078
+EDGE_SE2 242 243 0.648066 -0.017400 -0.010559 11.171248 3.692755 0.000000 237.869261 0.000000 2448.029575
+EDGE_SE2 243 244 0.642215 0.026261 0.062075 11.214953 4.895996 0.000000 241.951020 0.000000 2216.305562
+EDGE_SE2 244 245 0.634243 -0.022273 -0.061989 11.282517 -6.373688 0.000000 248.115451 0.000000 2216.664530
+EDGE_SE2 245 246 0.645668 -0.028614 -0.079256 11.390140 -7.976362 0.000000 239.124210 0.000000 2146.303161
+EDGE_SE2 246 247 0.643529 0.022831 0.100014 12.068378 14.809059 0.000000 240.209522 0.000000 2066.063111
+EDGE_SE2 247 248 0.564321 0.027061 0.024967 11.270232 -6.932385 0.000000 313.133504 0.000000 2379.689217
+EDGE_SE2 248 249 -0.035940 0.003373 0.183988 5772.276933 20220.354842 0.000000 70979.863375 0.000000 1783.386223
+EDGE_SE2 249 250 0.007750 -0.001049 -0.606852 338497.920927 -662461.020100 0.000000 1296530.178991 0.000000 968.251297
+EDGE_SE2 250 251 0.463939 -0.175406 -0.437806 13.410741 -30.065645 0.000000 404.193089 0.000000 1209.314960
+EDGE_SE2 251 252 0.574959 0.003510 0.002433 11.115040 -1.069896 0.000000 302.485346 0.000000 2487.879253
+EDGE_SE2 252 253 0.605120 -0.005928 -0.017244 11.125640 -1.950811 0.000000 273.056569 0.000000 2415.959973
+EDGE_SE2 253 254 0.610735 -0.012632 -0.047846 11.300633 -6.974744 0.000000 267.794244 0.000000 2276.905934
+EDGE_SE2 254 255 0.044400 0.000523 0.074991 213.390433 3196.298492 0.000000 50517.134043 0.000000 2163.367754
+EDGE_SE2 255 256 0.001043 -0.000895 -0.499566 2299182.592246 10791888.202847 0.000000 50655150.120270 0.000000 1111.754353
+EDGE_SE2 256 257 0.555824 -0.061442 -0.099167 11.147977 3.373126 0.000000 319.742706 0.000000 2069.248487
+EDGE_SE2 257 258 0.629719 0.018359 0.091632 12.050310 15.010875 0.000000 251.024412 0.000000 2097.913089
+EDGE_SE2 258 259 0.636152 0.019457 0.038906 11.127473 1.964002 0.000000 246.855618 0.000000 2316.261026
+EDGE_SE2 259 260 0.591139 -0.005281 -0.010083 11.111475 -0.316152 0.000000 286.144813 0.000000 2450.337378
+EDGE_SE2 260 261 0.038207 -0.011731 -0.314328 28.012479 -1028.395525 0.000000 62585.773083 0.000000 1447.213112
+EDGE_SE2 261 262 0.655511 -0.012976 0.004878 11.245910 5.462837 0.000000 232.497259 0.000000 2475.787308
+EDGE_SE2 262 263 0.621841 0.001156 0.011526 11.134237 2.392264 0.000000 258.583295 0.000000 2443.351271
+EDGE_SE2 263 264 0.608889 0.019368 0.094641 12.130010 16.192201 0.000000 268.435238 0.000000 2086.395259
+EDGE_SE2 264 265 0.612314 0.007199 0.017955 11.120930 1.584091 0.000000 266.671128 0.000000 2412.586253
+EDGE_SE2 265 266 0.576085 -0.083302 -0.132058 11.148980 3.279437 0.000000 295.110014 0.000000 1950.754657
+EDGE_SE2 266 267 0.757425 -0.007866 -0.038469 11.239778 -4.580310 0.000000 174.161685 0.000000 2318.210856
+EDGE_SE2 267 268 0.631857 -0.080953 -0.120705 11.121739 1.581391 0.000000 246.417934 0.000000 1990.478036
+EDGE_SE2 268 269 0.641922 0.003817 0.021827 11.169502 3.676650 0.000000 242.613796 0.000000 2394.336911
+EDGE_SE2 269 270 0.637667 0.034307 0.104727 11.718968 11.913668 0.000000 244.612698 0.000000 2048.472187
+EDGE_SE2 270 271 0.640010 -0.062261 -0.119686 11.230091 -5.238185 0.000000 241.725444 0.000000 1994.102659
+EDGE_SE2 271 272 0.644232 0.019193 0.057497 11.287428 6.360389 0.000000 240.553533 0.000000 2235.536271
+EDGE_SE2 272 273 0.634342 0.083237 0.206754 12.465423 17.719715 0.000000 242.954542 0.000000 1716.732048
+EDGE_SE2 273 274 0.640984 0.007900 0.019834 11.124210 1.744119 0.000000 243.341574 0.000000 2403.704272
+EDGE_SE2 274 275 0.606472 -0.086361 -0.177559 11.443959 -9.213419 0.000000 266.144138 0.000000 1802.912528
+EDGE_SE2 275 276 0.612197 0.023588 0.108696 12.366721 17.860495 0.000000 265.168738 0.000000 2033.831865
+EDGE_SE2 276 277 0.583581 0.010361 -0.030920 11.779645 -13.724550 0.000000 292.866956 0.000000 2352.285755
+EDGE_SE2 277 278 0.636078 -0.067917 -0.095289 11.139759 2.584894 0.000000 244.345909 0.000000 2083.927264
+EDGE_SE2 278 279 0.642761 -0.012725 -0.054157 11.383584 -7.926158 0.000000 241.680475 0.000000 2249.724898
+EDGE_SE2 279 280 0.638781 -0.006089 0.003079 11.148313 2.949856 0.000000 245.014031 0.000000 2484.675811
+EDGE_SE2 280 281 0.641856 -0.029617 -0.099276 11.763757 -12.263888 0.000000 241.562200 0.000000 2068.838150
+EDGE_SE2 281 282 0.639782 0.004798 0.040856 11.370470 7.772433 0.000000 244.033931 0.000000 2307.590321
+EDGE_SE2 282 283 0.642050 0.012891 -0.006948 11.280026 -6.249342 0.000000 242.317369 0.000000 2465.618735
+EDGE_SE2 283 284 0.634635 -0.008598 0.028031 11.520810 9.848040 0.000000 247.830973 0.000000 2365.525243
+EDGE_SE2 284 285 0.644186 0.019368 0.016799 11.151476 -3.044364 0.000000 240.720053 0.000000 2418.075116
+EDGE_SE2 285 286 0.616883 0.003268 0.049122 11.594142 11.014881 0.000000 262.290847 0.000000 2271.370705
+EDGE_SE2 286 287 0.041606 0.000178 -0.109420 754.499701 -6510.220695 0.000000 57024.326077 0.000000 2031.178201
+EDGE_SE2 287 288 0.009415 -0.003373 -0.619963 74221.251106 -262085.361102 0.000000 925608.832783 0.000000 952.642204
+EDGE_SE2 288 289 0.020008 -0.006408 -0.604589 19113.152514 -62948.109898 0.000000 207447.816761 0.000000 970.984702
+EDGE_SE2 289 290 0.454169 -0.104092 -0.231282 11.127187 -2.688060 0.000000 460.591382 0.000000 1649.016296
+EDGE_SE2 290 291 0.647578 0.004260 0.009723 11.113360 0.715048 0.000000 238.447481 0.000000 2452.084944
+EDGE_SE2 291 292 0.634089 -0.015008 -0.055281 11.348399 -7.502724 0.000000 248.336711 0.000000 2244.935000
+EDGE_SE2 292 293 0.642557 -0.005982 -0.023777 11.159473 -3.342559 0.000000 242.132375 0.000000 2385.224555
+EDGE_SE2 293 294 0.639112 0.001322 -0.000108 11.112218 -0.508677 0.000000 244.817748 0.000000 2499.460087
+EDGE_SE2 294 295 0.640372 -0.027705 -0.113609 12.259570 -16.292856 0.000000 242.253178 0.000000 2015.925806
+EDGE_SE2 295 296 0.642975 -0.021060 -0.046516 11.154844 -3.174767 0.000000 241.583458 0.000000 2282.696976
+EDGE_SE2 296 297 0.642345 0.000782 -0.012863 11.156958 -3.255777 0.000000 242.314814 0.000000 2436.904980
+EDGE_SE2 297 298 0.647985 0.003784 0.003363 11.112504 -0.562400 0.000000 238.150885 0.000000 2483.269445
+EDGE_SE2 298 299 0.612845 -0.007635 0.065661 12.664708 19.847274 0.000000 264.661036 0.000000 2201.414711
+EDGE_SE2 299 300 0.612360 0.028900 0.046427 11.111248 -0.186667 0.000000 266.084327 0.000000 2283.085285
+EDGE_SE2 300 301 0.590205 -0.014952 -0.054929 11.352681 -8.158527 0.000000 286.648280 0.000000 2246.433393
+EDGE_SE2 301 302 0.327130 -0.001110 -0.017014 11.282416 -12.575459 0.000000 934.273069 0.000000 2417.052846
+EDGE_SE2 302 303 0.000000 0.000000 0.007958 11.135739 3.094647 0.000000 399.975372 0.000000 2460.679983
+EDGE_SE2 303 304 0.531735 -0.000572 0.013349 11.182383 4.940694 0.000000 353.608097 0.000000 2434.568072
+EDGE_SE2 304 305 0.632029 0.091742 0.189082 11.583394 10.503320 0.000000 244.699503 0.000000 1768.138981
+EDGE_SE2 305 306 0.638032 0.009278 -0.014535 11.309292 -6.814055 0.000000 245.399171 0.000000 2428.879337
+EDGE_SE2 306 307 0.649045 -0.016359 -0.033059 11.125080 -1.777236 0.000000 237.218596 0.000000 2342.554790
+EDGE_SE2 307 308 0.638862 -0.008726 -0.051832 11.451746 -8.918684 0.000000 244.624962 0.000000 2259.681604
+EDGE_SE2 308 309 0.645288 0.030453 0.096996 11.678208 11.369540 0.000000 239.055109 0.000000 2077.446846
+EDGE_SE2 309 310 0.636777 0.000884 -0.032322 11.378630 -7.932902 0.000000 246.350008 0.000000 2345.900799
+EDGE_SE2 310 311 0.290424 -0.002112 0.179746 51.710880 214.552149 0.000000 1144.926065 0.000000 1796.234285
+EDGE_SE2 311 312 0.007354 0.003264 1.002917 471360.416969 711283.404228 0.000000 1073363.876974 0.000000 623.180856
+EDGE_SE2 312 313 0.200119 0.102327 0.503683 13.003444 61.001684 0.000000 1977.575148 0.000000 1105.674845
+EDGE_SE2 313 314 0.633848 0.018391 0.043519 11.161147 3.447475 0.000000 248.643057 0.000000 2295.827675
+EDGE_SE2 314 315 0.633704 0.002276 -0.000875 11.115856 -1.062415 0.000000 249.007791 0.000000 2495.630735
+EDGE_SE2 315 316 0.639305 0.015820 0.052631 11.292626 6.506496 0.000000 244.340479 0.000000 2256.252482
+EDGE_SE2 316 317 0.637745 0.004302 0.011142 11.115650 1.032197 0.000000 245.854624 0.000000 2445.207439
+EDGE_SE2 317 318 0.636745 0.035394 0.095957 11.494620 9.481044 0.000000 245.500106 0.000000 2081.387677
+EDGE_SE2 318 319 0.348842 0.011538 0.072712 12.383431 32.072340 0.000000 819.582938 0.000000 2172.569763
+EDGE_SE2 319 320 0.000816 -0.000527 0.973228 106005797.819726 2536098.274165 0.000000 60685.105012 0.000000 642.074570
+EDGE_SE2 320 321 0.006777 0.006256 1.044793 102222.634261 331234.073682 0.000000 1073432.269379 0.000000 597.917382
+EDGE_SE2 321 322 0.006473 0.002839 1.001084 615262.184536 923437.444301 0.000000 1386009.040037 0.000000 624.323050
+EDGE_SE2 322 323 0.016353 0.013170 0.997277 22353.154021 67589.307695 0.000000 204482.767224 0.000000 626.705357
+EDGE_SE2 323 324 0.008916 0.001230 0.663199 311347.556233 536104.854899 0.000000 923155.252921 0.000000 903.756801
+EDGE_SE2 324 325 0.003144 -0.000405 -0.524891 1487579.272379 -3549001.141685 0.000000 8467125.043520 0.000000 1075.133530
+EDGE_SE2 325 326 0.023808 -0.007961 -0.592174 11258.329132 -40719.337055 0.000000 147431.069280 0.000000 986.186273
+EDGE_SE2 326 327 0.020978 -0.009992 -0.620226 5671.563195 -31879.996101 0.000000 179561.107529 0.000000 952.332958
+EDGE_SE2 327 328 0.643658 -0.034894 -0.045241 11.129369 2.047184 0.000000 240.647976 0.000000 2288.269306
+EDGE_SE2 328 329 0.649334 -0.010852 -0.054672 11.436629 -8.570843 0.000000 236.780423 0.000000 2247.528337
+EDGE_SE2 329 330 0.639632 -0.008474 -0.018872 11.118489 -1.311825 0.000000 244.371181 0.000000 2408.245480
+EDGE_SE2 330 331 0.641038 0.003713 -0.014179 11.203728 -4.636800 0.000000 243.249680 0.000000 2430.584821
+EDGE_SE2 331 332 0.640252 -0.011677 -0.018427 11.111120 -0.044254 0.000000 243.867115 0.000000 2410.350498
+EDGE_SE2 332 333 0.177633 -0.001729 0.065170 28.796073 235.654693 0.000000 3151.244188 0.000000 2203.444704
+EDGE_SE2 333 334 0.000905 -0.002029 1.057518 13067665.297415 -9690930.296947 0.000000 7186773.836950 0.000000 590.544626
+EDGE_SE2 334 335 0.024703 0.015296 0.997066 21742.343151 45843.877395 0.000000 96722.659299 0.000000 626.837793
+EDGE_SE2 335 336 0.010478 0.002030 0.946908 412732.144616 438156.323325 0.000000 465170.257567 0.000000 659.552164
+EDGE_SE2 336 337 0.008745 0.002954 0.985008 440385.721295 568301.950425 0.000000 733402.863015 0.000000 634.476419
+EDGE_SE2 337 338 -0.003685 -0.001824 0.981724 1470665.482891 2556461.697178 0.000000 4443948.812959 0.000000 636.580801
+EDGE_SE2 338 339 -0.005129 -0.003808 1.041677 377018.548764 884152.776785 0.000000 2073514.322517 0.000000 599.744033
+EDGE_SE2 339 340 0.010570 0.010289 1.011780 25946.779143 106050.417947 0.000000 433649.108522 0.000000 617.702041
+EDGE_SE2 340 341 0.113717 0.080150 0.628571 12.212286 75.337385 0.000000 5165.350612 0.000000 942.598218
+EDGE_SE2 341 342 0.654766 0.022058 0.099815 12.080273 14.632015 0.000000 232.019342 0.000000 2066.810844
+EDGE_SE2 342 343 0.628741 0.054742 0.130801 11.574390 10.533194 0.000000 250.595866 0.000000 1955.093991
+EDGE_SE2 343 344 0.635892 -0.007155 -0.010075 11.111438 0.277943 0.000000 247.273507 0.000000 2450.376193
+EDGE_SE2 344 345 0.267580 0.003485 -0.027538 13.388942 -56.127772 0.000000 1394.149289 0.000000 2367.795687
+EDGE_SE2 345 346 0.004489 0.000038 -0.647423 1844936.688291 -2397918.213433 0.000000 3116674.368121 0.000000 921.148732
+EDGE_SE2 346 347 0.072838 -0.046842 -0.558829 13.253512 168.933111 0.000000 13331.862665 0.000000 1028.828663
+EDGE_SE2 347 348 0.589079 -0.006098 -0.016843 11.122785 -1.798313 0.000000 288.130205 0.000000 2417.865855
+EDGE_SE2 348 349 0.616820 -0.017333 -0.040458 11.149561 -3.109556 0.000000 262.589175 0.000000 2309.356075
+EDGE_SE2 349 350 0.785503 -0.000917 -0.019918 11.164179 -2.829897 0.000000 162.017193 0.000000 2403.308352
+EDGE_SE2 350 351 0.270645 -0.005037 -0.029292 11.265595 -14.459903 0.000000 1364.581559 0.000000 2359.732718
+EDGE_SE2 351 352 0.002244 -0.000330 -0.288296 389945.087215 -2724716.373664 0.000000 19039335.129753 0.000000 1506.290344
+EDGE_SE2 352 353 0.003402 -0.001192 -0.665425 800995.211276 -2349889.351851 0.000000 6894005.592158 0.000000 901.342500
+EDGE_SE2 353 354 -0.005763 0.001670 -0.603397 277124.929036 -832459.339385 0.000000 2500747.295676 0.000000 972.428940
+EDGE_SE2 354 355 0.000000 0.000000 -0.720990 180.577269 -192.833418 0.000000 230.533842 0.000000 844.079125
+EDGE_SE2 355 356 0.003943 -0.001205 -0.575253 444990.541595 -1555501.608157 0.000000 5437532.684522 0.000000 1007.486830
+EDGE_SE2 356 357 0.020153 -0.008599 -0.653072 12735.537924 -49883.324785 0.000000 195567.746252 0.000000 914.863854
+EDGE_SE2 357 358 0.015309 -0.003110 -0.615454 66643.110857 -151211.449053 0.000000 343163.086320 0.000000 957.967591
+EDGE_SE2 358 359 0.006974 -0.000995 -0.614029 417035.012297 -816381.545249 0.000000 1598190.077659 0.000000 959.659886
+EDGE_SE2 359 360 0.004457 -0.000580 -0.176301 10913.841058 -232052.237339 0.000000 4938979.710352 0.000000 1806.770854
+EDGE_SE2 360 361 0.010594 0.005702 0.919376 117786.647020 259806.659966 0.000000 573130.987341 0.000000 678.609427
+EDGE_SE2 361 362 0.219803 0.130838 0.533743 11.126432 -4.821230 0.000000 1528.288566 0.000000 1062.759073
+EDGE_SE2 362 363 0.297072 -0.003532 -0.006476 11.143964 6.070793 0.000000 1132.926894 0.000000 2467.931845
+EDGE_SE2 363 364 0.289348 0.182399 0.614616 13.404127 43.923133 0.000000 852.466620 0.000000 958.962236
+EDGE_SE2 364 365 0.292841 -0.019896 -0.497082 210.238012 -435.053006 0.000000 961.616130 0.000000 1115.446721
+EDGE_SE2 365 366 0.158985 -0.083838 -0.554071 25.686079 -211.524041 0.000000 3080.923734 0.000000 1035.138105
+EDGE_SE2 366 367 0.639497 -0.004946 0.002087 11.133620 2.291973 0.000000 244.487349 0.000000 2489.597576
+EDGE_SE2 367 368 0.604131 -0.012617 -0.052944 11.381139 -8.419024 0.000000 273.602223 0.000000 2254.911286
+EDGE_SE2 368 369 0.002209 0.000313 -0.259186 3043052.869717 -7202482.111400 0.000000 17047344.890980 0.000000 1576.740546
+EDGE_SE2 369 370 0.005991 -0.002050 -0.599321 177021.973379 -640449.340665 0.000000 2317243.809168 0.000000 977.391885
+EDGE_SE2 370 371 0.006708 -0.002639 -0.557206 63344.214539 -343349.901593 0.000000 1861425.577547 0.000000 1030.974377
+EDGE_SE2 371 372 0.558575 -0.019962 -0.032348 11.114630 1.042696 0.000000 320.094134 0.000000 2345.782636
+EDGE_SE2 372 373 0.602488 0.010152 -0.002327 11.208284 -5.066873 0.000000 275.312725 0.000000 2488.405486
+EDGE_SE2 373 374 0.632591 -0.017325 -0.065949 11.465862 -9.193251 0.000000 249.351067 0.000000 2200.225307
+EDGE_SE2 374 375 0.469417 0.004030 -0.028771 11.728554 -16.521047 0.000000 453.167816 0.000000 2362.123399
+EDGE_SE2 375 376 0.002158 0.000483 0.698524 4333313.980583 8354996.990813 0.000000 16109195.449061 0.000000 866.555999
+EDGE_SE2 376 377 0.046225 0.038326 0.699019 12.380728 187.607270 0.000000 27733.237753 0.000000 866.051140
+EDGE_SE2 377 378 0.665310 0.013616 0.055080 11.368301 7.426696 0.000000 225.566926 0.000000 2245.790433
+EDGE_SE2 378 379 0.642743 0.038423 0.085729 11.266862 5.984327 0.000000 241.043246 0.000000 2120.787390
+EDGE_SE2 379 380 0.640645 0.038346 0.120298 11.958441 13.985039 0.000000 241.931786 0.000000 1991.924564
+EDGE_SE2 380 381 0.233459 0.003584 0.150906 44.408710 244.130938 0.000000 1801.027395 0.000000 1887.384136
+EDGE_SE2 381 382 0.006327 0.000255 1.053123 1795131.477569 1120171.329981 0.000000 699008.143264 0.000000 593.075621
+EDGE_SE2 382 383 -0.003556 -0.002021 0.980056 1193066.389244 2388759.272445 0.000000 4782832.968807 0.000000 637.653764
+EDGE_SE2 383 384 0.001991 0.002244 0.957091 138704.428768 1233640.966374 0.000000 10972926.458664 0.000000 652.706547
+EDGE_SE2 384 385 0.011270 0.001792 1.022982 445019.439592 379059.233315 0.000000 322894.736351 0.000000 610.880091
+EDGE_SE2 385 386 0.168577 0.055826 0.222392 40.994230 -305.838725 0.000000 3141.216954 0.000000 1673.088872
+EDGE_SE2 386 387 0.606264 0.162988 0.328749 12.170230 15.994975 0.000000 252.669738 0.000000 1415.970180
+EDGE_SE2 387 388 0.635832 0.013644 0.010758 11.138130 -2.525694 0.000000 247.211302 0.000000 2447.065724
+EDGE_SE2 388 389 0.627947 -0.024187 -0.080320 11.534345 -10.113978 0.000000 252.803888 0.000000 2142.077483
+EDGE_SE2 389 390 0.069191 0.001300 0.478702 4122.849667 8300.847325 0.000000 16769.002054 0.000000 1143.348663
+EDGE_SE2 390 391 -0.133725 -0.033239 0.382997 112.537800 723.030020 0.000000 5165.300931 0.000000 1307.066045
+EDGE_SE2 391 392 -0.002743 0.000191 1.047762 10690557.469801 5209631.734700 0.000000 2538727.272155 0.000000 596.185006
+EDGE_SE2 392 393 0.028217 0.013447 1.259453 54184.105027 51083.362632 0.000000 48181.052425 0.000000 489.703700
+EDGE_SE2 393 394 0.008510 0.003621 0.998557 368727.424224 543264.764209 0.000000 800454.686659 0.000000 625.902660
+EDGE_SE2 394 395 -0.234595 -0.069505 0.339597 15.518106 85.399492 0.000000 1665.996927 0.000000 1393.130101
+EDGE_SE2 395 396 0.000000 0.000000 0.001250 11.111719 0.486111 0.000000 399.999392 0.000000 2493.761699
+EDGE_SE2 396 397 0.001351 -0.000419 -0.009641 4125762.827775 13757530.022207 0.000000 45875198.303653 0.000000 2452.483262
+EDGE_SE2 397 398 0.004038 0.000754 0.199105 1257.017158 85923.998064 0.000000 5925765.672764 0.000000 1738.703710
+EDGE_SE2 398 399 0.122070 0.031296 0.300741 26.669772 312.344207 0.000000 6281.503348 0.000000 1477.604991
+EDGE_SE2 399 400 0.657179 0.003449 0.051415 11.580586 10.161892 0.000000 231.067499 0.000000 2261.474377
+EDGE_SE2 400 401 0.635899 -0.025106 -0.091900 11.758968 -12.342900 0.000000 246.266720 0.000000 2096.883376
+EDGE_SE2 401 402 0.629497 -0.118990 -0.266463 12.583010 -18.442000 0.000000 242.178169 0.000000 1558.672941
+EDGE_SE2 402 403 0.633089 -0.005208 -0.033694 11.265698 -6.068382 0.000000 249.328787 0.000000 2339.677603
+EDGE_SE2 403 404 0.592291 -0.016693 -0.078703 11.809289 -13.806384 0.000000 284.130876 0.000000 2148.504341
+EDGE_SE2 404 405 0.003136 0.000509 0.534523 1319098.360620 3365183.519520 0.000000 8585083.951642 0.000000 1061.678944
+EDGE_SE2 405 406 -0.004868 -0.003220 0.979360 434468.323030 1042340.456046 0.000000 2500772.052588 0.000000 638.102476
+EDGE_SE2 406 407 0.360175 0.041381 0.128315 11.256473 10.438221 0.000000 760.666018 0.000000 1963.718742
+EDGE_SE2 407 408 0.616703 -0.006846 -0.037807 11.290664 -6.721434 0.000000 262.722906 0.000000 2321.169297
+EDGE_SE2 408 409 0.297889 -0.008429 -0.099428 16.743853 -79.045672 0.000000 1120.378773 0.000000 2068.266140
+EDGE_SE2 409 410 0.004317 -0.001082 -0.627510 701653.157370 -1746561.647658 0.000000 4347637.661335 0.000000 943.827609
+EDGE_SE2 410 411 -0.000994 0.000097 -0.588953 22378715.073239 -41773418.211876 0.000000 77976755.075261 0.000000 990.188564
+EDGE_SE2 411 412 0.546073 -0.101761 -0.202851 11.219546 -5.824669 0.000000 323.987402 0.000000 1727.890996
+EDGE_SE2 412 413 0.631438 -0.020731 -0.079531 11.633150 -11.167657 0.000000 250.014003 0.000000 2145.209801
+EDGE_SE2 413 414 0.633214 0.018368 0.103733 12.438356 17.726525 0.000000 247.864474 0.000000 2052.163475
+EDGE_SE2 414 415 0.642786 -0.007808 0.006683 11.192966 4.346517 0.000000 241.911433 0.000000 2466.917009
+EDGE_SE2 415 416 0.306053 0.007945 -0.055552 18.109521 -85.672115 0.000000 1059.879484 0.000000 2243.782429
+EDGE_SE2 416 417 0.267976 -0.110772 -0.425050 12.399497 -38.940001 0.000000 1188.028820 0.000000 1231.061654
+EDGE_SE2 417 418 0.438509 -0.005278 -0.045468 11.679675 -16.999880 0.000000 519.402521 0.000000 2287.275721
+EDGE_SE2 418 419 -0.008030 -0.002982 0.430439 7637.313369 101662.498186 0.000000 1355241.825942 0.000000 1221.803385
+EDGE_SE2 419 420 -0.065315 -0.007710 0.215762 233.503005 2255.992653 0.000000 22896.400499 0.000000 1691.386574
+EDGE_SE2 420 421 -0.013305 -0.007156 0.966654 91010.544219 177739.023434 0.000000 347168.883115 0.000000 646.374313
+EDGE_SE2 421 422 -0.003762 0.002250 1.237922 4986989.532826 -1042930.375544 0.000000 218119.888862 0.000000 499.171886
+EDGE_SE2 422 423 0.004840 0.001590 0.345136 2976.169439 106843.491501 0.000000 3850030.373965 0.000000 1381.680463
+EDGE_SE2 423 424 0.000000 0.000000 0.000279 11.111141 0.108500 0.000000 399.999970 0.000000 2498.605584
+EDGE_SE2 424 425 -0.001184 -0.000773 0.011635 14427656.748816 -22661090.484365 0.000000 35593138.003454 0.000000 2442.824774
+EDGE_SE2 425 426 0.000000 0.000000 -0.009217 11.144147 -3.584186 0.000000 399.966964 0.000000 2454.544407
+EDGE_SE2 426 427 0.032570 0.000297 0.003027 14.602102 -573.593983 0.000000 94256.571445 0.000000 2484.933444
+EDGE_SE2 427 428 0.662478 0.017221 -0.005659 11.327981 -6.850147 0.000000 227.483295 0.000000 2471.943383
+EDGE_SE2 428 429 0.646109 -0.008556 -0.041027 11.287389 -6.342667 0.000000 239.327268 0.000000 2306.832289
+EDGE_SE2 429 430 0.343414 -0.005292 -0.046373 11.913023 -25.889333 0.000000 846.935174 0.000000 2283.320937
+EDGE_SE2 430 431 -0.023101 -0.000669 0.051637 107.302578 4242.658469 0.000000 187139.464787 0.000000 2260.519686
+EDGE_SE2 431 432 0.009902 -0.002457 -0.632717 138557.863737 -337512.999974 0.000000 822224.717657 0.000000 937.817169
+EDGE_SE2 432 433 0.001378 -0.000302 -0.678362 9999210.149914 -20053649.036543 0.000000 40218116.393371 0.000000 887.500758
+EDGE_SE2 433 434 0.513100 -0.123605 -0.228760 11.131390 2.656033 0.000000 358.981365 0.000000 1655.792374
+EDGE_SE2 434 435 0.631214 0.005719 -0.028704 11.453001 -9.049106 0.000000 250.621585 0.000000 2362.431102
+EDGE_SE2 435 436 0.631793 -0.021639 -0.009165 11.261393 5.992726 0.000000 250.081133 0.000000 2454.797368
+EDGE_SE2 436 437 0.639424 0.009664 0.007564 11.124412 -1.761949 0.000000 244.511544 0.000000 2462.604819
+EDGE_SE2 437 438 0.468926 -0.010782 -0.032675 11.152708 -4.294523 0.000000 454.487167 0.000000 2344.297271
+EDGE_SE2 438 439 0.003173 -0.000464 -0.440138 821397.131579 -2704073.669587 0.000000 8902055.008072 0.000000 1205.401670
+EDGE_SE2 439 440 -0.014852 0.005433 -0.648635 34474.470288 -112210.861458 0.000000 365363.698028 0.000000 919.794858
+EDGE_SE2 440 441 -0.024049 0.006849 -0.627372 18805.328328 -51499.965243 0.000000 141131.456239 0.000000 943.987688
+EDGE_SE2 441 442 -0.014780 0.003839 -0.634781 59210.969468 -147922.954315 0.000000 369626.867304 0.000000 935.450222
+EDGE_SE2 442 443 -0.000800 0.000601 -0.571864 520464.172419 7194009.672200 0.000000 99439862.677541 0.000000 1011.835875
+EDGE_SE2 443 444 0.017737 -0.005934 -0.596674 20918.075426 -74425.493858 0.000000 264954.124953 0.000000 980.635254
+EDGE_SE2 444 445 0.013295 -0.004859 -0.663772 47441.842994 -146367.463524 0.000000 451689.453992 0.000000 903.134403
+EDGE_SE2 445 446 0.005858 0.000522 0.198590 34655.344042 314604.971132 0.000000 2856945.136973 0.000000 1740.198174
+EDGE_SE2 446 447 0.027440 0.012672 0.626113 4057.920343 20653.549968 0.000000 105419.866954 0.000000 945.449998
+EDGE_SE2 447 448 0.642139 0.024176 0.015042 11.228997 -5.217769 0.000000 242.055366 0.000000 2426.453558
+EDGE_SE2 448 449 0.651924 0.033077 0.098456 11.620735 10.662081 0.000000 234.177343 0.000000 2071.928088
+EDGE_SE2 449 450 0.646061 0.005408 0.011249 11.113005 0.657701 0.000000 239.562562 0.000000 2444.690013
+EDGE_SE2 450 451 0.475342 0.014049 0.039952 11.157786 4.485326 0.000000 442.142124 0.000000 2311.603906
+EDGE_SE2 451 452 0.003128 0.000025 -0.382848 1482988.188246 -3599772.040321 0.000000 8738081.943140 0.000000 1307.347729
+EDGE_SE2 452 453 -0.001414 0.000044 -0.628930 15847694.024322 -23260624.874036 0.000000 34141069.617498 0.000000 942.182786
+EDGE_SE2 453 454 0.248647 -0.103850 -0.427200 12.471635 -43.090213 0.000000 1375.854801 0.000000 1227.355391
+EDGE_SE2 454 455 0.599080 -0.006587 -0.019767 11.131695 -2.346400 0.000000 278.577271 0.000000 2404.020135
+EDGE_SE2 455 456 0.632985 -0.015395 -0.063626 11.479192 -9.358780 0.000000 249.066485 0.000000 2209.846555
+EDGE_SE2 456 457 0.357560 -0.010532 -0.086657 13.629849 -43.977817 0.000000 778.975316 0.000000 2117.166652
+EDGE_SE2 457 458 0.008700 -0.003028 -0.643446 108644.728053 -340906.127357 0.000000 1069817.962261 0.000000 925.612330
+EDGE_SE2 458 459 -0.005152 0.003223 -0.605857 5968.917352 -126872.556203 0.000000 2701785.030428 0.000000 969.451909
+EDGE_SE2 459 460 0.416054 -0.104238 -0.255576 11.165314 -5.371986 0.000000 543.523585 0.000000 1585.820389
+EDGE_SE2 460 461 0.649228 -0.030811 -0.086883 11.462229 -8.893307 0.000000 236.365424 0.000000 2116.286282
+EDGE_SE2 461 462 0.546102 -0.010087 -0.039056 11.248462 -6.670465 0.000000 335.062438 0.000000 2315.592315
+EDGE_SE2 462 463 0.001368 -0.000392 0.843270 40115968.021050 19291406.563907 0.000000 9277076.794710 0.000000 735.803923
+EDGE_SE2 463 464 0.219986 0.165070 0.680690 12.900768 48.403186 0.000000 1320.227268 0.000000 885.043825
+EDGE_SE2 464 465 0.606621 0.010649 0.008756 11.131273 -2.291927 0.000000 271.643258 0.000000 2456.788366
+EDGE_SE2 465 466 0.582724 -0.019176 -0.054453 11.242627 -6.100006 0.000000 294.042673 0.000000 2248.462015
+EDGE_SE2 466 467 0.609463 -0.011568 -0.042219 11.250443 -5.994134 0.000000 268.982117 0.000000 2301.558596
+EDGE_SE2 467 468 0.645554 -0.004365 -0.036329 11.311111 -6.762186 0.000000 239.747111 0.000000 2327.794866
+EDGE_SE2 468 469 0.640915 -0.033457 -0.083791 11.342903 -7.324322 0.000000 242.550344 0.000000 2128.378819
+EDGE_SE2 469 470 0.496055 0.004661 0.018154 11.141432 3.461691 0.000000 406.321439 0.000000 2411.643257
+EDGE_SE2 470 471 0.003172 -0.000201 -0.200803 186163.578620 -1344733.466553 0.000000 9714134.809108 0.000000 1733.789946
+EDGE_SE2 471 472 0.023951 -0.007826 -0.634338 15457.850073 -46841.273730 0.000000 142054.355974 0.000000 935.957765
+EDGE_SE2 472 473 0.005795 -0.000612 -0.642279 770586.651464 -1294281.400636 0.000000 2173924.317941 0.000000 926.928274
+EDGE_SE2 473 474 0.006655 -0.002332 -0.633006 171083.550792 -560999.777087 0.000000 1839703.994891 0.000000 937.485259
+EDGE_SE2 474 475 0.004438 -0.002279 -0.575983 41353.024051 -405427.745271 0.000000 3975919.455633 0.000000 1006.553705
+EDGE_SE2 475 476 0.004920 -0.000853 -0.653637 861490.486597 -1647075.461555 0.000000 3149079.624245 0.000000 914.238796
+EDGE_SE2 476 477 -0.005593 0.002916 -0.561690 16496.747941 -202882.586381 0.000000 2496811.464145 0.000000 1025.062106
+EDGE_SE2 477 478 -0.008770 0.002879 -0.629412 110767.500374 -343119.326612 0.000000 1062982.494329 0.000000 941.625450
+EDGE_SE2 478 479 -0.005316 0.000950 -0.456182 260653.569609 -908664.641767 0.000000 3167842.768150 0.000000 1178.986119
+EDGE_SE2 479 480 -0.002143 -0.000584 0.559864 1701134.587605 5621159.573829 0.000000 18574462.284739 0.000000 1027.463821
+EDGE_SE2 480 481 0.016780 0.006185 0.998459 113112.243905 150237.129574 0.000000 199577.592411 0.000000 625.964239
+EDGE_SE2 481 482 0.002129 0.000684 0.334515 11133.789831 471436.097728 0.000000 19981887.764379 0.000000 1403.760085
+EDGE_SE2 482 483 0.000000 0.000000 -0.006313 11.126610 -2.454990 0.000000 399.984501 0.000000 2468.731408
+EDGE_SE2 483 484 0.461514 0.003388 0.034531 11.449878 12.456397 0.000000 469.130063 0.000000 2335.893245
+EDGE_SE2 484 485 0.630348 0.014297 -0.002799 11.267128 -6.122690 0.000000 251.389266 0.000000 2486.063539
+EDGE_SE2 485 486 0.640080 -0.006164 0.008991 11.191872 4.336635 0.000000 243.975902 0.000000 2455.644098
+EDGE_SE2 486 487 0.638592 0.022157 0.027672 11.122603 -1.639115 0.000000 244.911905 0.000000 2367.178245
+EDGE_SE2 487 488 0.641671 0.002950 0.035457 11.331743 7.147283 0.000000 242.644669 0.000000 2331.717176
+EDGE_SE2 488 489 0.486254 0.015193 0.029736 11.112036 -0.616989 0.000000 422.520775 0.000000 2357.698224
+EDGE_SE2 489 490 0.004012 0.001331 0.483683 148092.465768 898284.334868 0.000000 5449142.422335 0.000000 1135.684680
+EDGE_SE2 490 491 0.003142 0.002440 0.933695 460500.560493 1642380.154927 0.000000 5857718.767430 0.000000 668.596440
+EDGE_SE2 491 492 0.234443 0.072984 0.301949 11.111148 0.245247 0.000000 1658.639702 0.000000 1474.864302
+EDGE_SE2 492 493 0.622117 -0.019196 -0.055751 11.264294 -6.149470 0.000000 257.979045 0.000000 2242.936641
+EDGE_SE2 493 494 0.632902 -0.009810 -0.061610 11.617811 -10.980862 0.000000 249.080844 0.000000 2218.247533
+EDGE_SE2 494 495 0.635286 0.054465 0.110803 11.261154 5.934337 0.000000 245.819252 0.000000 2026.123532
+EDGE_SE2 495 496 0.641209 0.012116 0.121000 13.521763 23.526915 0.000000 240.723619 0.000000 1989.430553
+EDGE_SE2 496 497 0.639602 -0.025661 -0.083377 11.547127 -10.068553 0.000000 243.615831 0.000000 2130.005800
+EDGE_SE2 497 498 0.634982 -0.033636 -0.099467 11.622457 -10.978306 0.000000 246.809304 0.000000 2068.119413
+EDGE_SE2 498 499 0.638794 -0.029903 -0.015370 11.341287 7.326250 0.000000 244.297416 0.000000 2424.886152
+EDGE_SE2 499 500 0.581639 0.165523 0.331283 11.876261 14.147113 0.000000 272.681816 0.000000 1410.584918
+EDGE_SE2 500 501 0.608658 -0.019295 -0.065817 11.412115 -8.816677 0.000000 269.359185 0.000000 2200.770331
+EDGE_SE2 501 502 0.717458 -0.037860 -0.078159 11.229253 -4.643405 0.000000 193.613030 0.000000 2150.673003
+EDGE_SE2 502 503 0.468033 -0.006282 -0.011528 11.112706 0.842757 0.000000 456.422908 0.000000 2443.341609
+EDGE_SE2 503 504 0.001010 -0.000329 0.882265 76783402.732445 30131648.184749 0.000000 11824394.003794 0.000000 705.632337
+EDGE_SE2 504 505 0.222895 0.156032 0.638914 12.174041 37.721370 0.000000 1349.770700 0.000000 930.738499
+EDGE_SE2 505 506 0.625769 -0.021473 -0.145256 14.102191 -26.846905 0.000000 252.079673 0.000000 1906.052494
+EDGE_SE2 506 507 0.635814 -0.018204 -0.072178 11.558631 -10.268279 0.000000 246.715411 0.000000 2174.734405
+EDGE_SE2 507 508 0.638204 -0.013687 -0.007658 11.155629 3.229265 0.000000 245.359315 0.000000 2462.145389
+EDGE_SE2 508 509 0.642039 -0.008726 -0.051671 11.446573 -8.804866 0.000000 242.212186 0.000000 2260.373525
+EDGE_SE2 509 510 0.372102 -0.006043 -0.009950 11.139237 4.471542 0.000000 722.013535 0.000000 2450.982789
+EDGE_SE2 510 511 0.002084 -0.003553 0.891003 5160201.305808 -1945038.253710 0.000000 733157.306436 0.000000 699.126192
+EDGE_SE2 511 512 0.007335 0.005942 1.221397 297144.725264 495141.758266 0.000000 825112.510283 0.000000 506.626201
+EDGE_SE2 512 513 -0.002181 -0.000566 0.972737 8538321.615481 9762487.124922 0.000000 11162190.656524 0.000000 642.394025
+EDGE_SE2 513 514 0.090094 0.023767 0.232272 18.681434 -295.052416 0.000000 11510.742828 0.000000 1646.367741
+EDGE_SE2 514 515 0.658710 0.013018 0.004928 11.159348 -3.251856 0.000000 230.330528 0.000000 2475.540949
+EDGE_SE2 515 516 0.637378 -0.008635 0.019744 11.371458 7.817478 0.000000 245.848124 0.000000 2404.128580
+EDGE_SE2 516 517 0.633811 0.029113 0.032052 11.156620 -3.285893 0.000000 248.362090 0.000000 2347.128404
+EDGE_SE2 517 518 0.634675 0.007993 0.028090 11.168044 3.673667 0.000000 248.158131 0.000000 2365.253746
+EDGE_SE2 518 519 0.560153 0.002654 -0.012150 11.198833 -5.193662 0.000000 318.608437 0.000000 2440.339501
+EDGE_SE2 519 520 0.197101 -0.000544 0.405434 414.955475 933.778631 0.000000 2170.216473 0.000000 1265.665952
+EDGE_SE2 520 521 0.006002 0.005024 1.019492 163989.160959 490677.362406 0.000000 1468282.469392 0.000000 612.993310
+EDGE_SE2 521 522 0.414779 0.108184 0.270025 11.229248 7.935203 0.000000 544.113259 0.000000 1549.942078
+EDGE_SE2 522 523 0.644866 -0.002177 -0.013262 11.133525 -2.267210 0.000000 240.444921 0.000000 2434.986160
+EDGE_SE2 523 524 0.606582 -0.016880 -0.047652 11.213538 -5.164087 0.000000 271.469885 0.000000 2277.749269
+EDGE_SE2 524 525 0.576823 0.002529 0.018772 11.171018 4.163585 0.000000 300.483332 0.000000 2408.718278
+EDGE_SE2 525 526 0.607148 -0.019364 -0.063586 11.372241 -8.233863 0.000000 270.738644 0.000000 2210.012777
+EDGE_SE2 526 527 0.632532 -0.013902 -0.038859 11.179151 -4.029527 0.000000 249.750981 0.000000 2316.470615
+EDGE_SE2 527 528 0.639965 -0.031254 -0.079842 11.335080 -7.212289 0.000000 243.362638 0.000000 2143.974316
+EDGE_SE2 528 529 0.630138 0.005118 -0.025519 11.383434 -8.091842 0.000000 251.553301 0.000000 2377.128104
+EDGE_SE2 529 530 0.643013 -0.010371 -0.027118 11.138973 -2.535041 0.000000 241.767362 0.000000 2369.732519
+EDGE_SE2 530 531 0.632204 -0.021106 -0.076364 11.552220 -10.254093 0.000000 249.479589 0.000000 2157.852130
+EDGE_SE2 531 532 0.210203 0.000529 0.053978 17.069737 115.687987 0.000000 2257.218094 0.000000 2250.489117
+EDGE_SE2 532 533 0.010481 0.007945 1.006775 71059.615350 189815.528908 0.000000 507128.543079 0.000000 620.787044
+EDGE_SE2 533 534 0.004524 0.002070 0.671821 233294.669406 942460.043629 0.000000 3807527.338703 0.000000 894.459037
+EDGE_SE2 534 535 0.000000 0.000000 0.001338 11.111807 0.520333 0.000000 399.999304 0.000000 2493.323403
+EDGE_SE2 535 536 0.357295 0.039869 0.132965 11.474755 16.648687 0.000000 773.337063 0.000000 1947.632537
+EDGE_SE2 536 537 0.617574 -0.018145 -0.055950 11.288271 -6.664110 0.000000 261.790435 0.000000 2242.091332
+EDGE_SE2 537 538 0.579730 -0.014385 -0.025102 11.111136 -0.083914 0.000000 297.359512 0.000000 2379.062475
+EDGE_SE2 538 539 0.638569 -0.022758 -0.062503 11.280003 -6.281777 0.000000 244.755892 0.000000 2214.520366
+EDGE_SE2 539 540 0.636808 -0.030043 -0.090399 11.550435 -10.149862 0.000000 245.607132 0.000000 2102.660323
+EDGE_SE2 540 541 0.624998 0.051843 0.165279 12.763015 19.972919 0.000000 252.600591 0.000000 1841.111831
+EDGE_SE2 541 542 0.637879 0.044546 0.058251 11.141827 -2.677719 0.000000 244.543713 0.000000 2232.351783
+EDGE_SE2 542 543 0.119005 -0.001027 -0.027249 13.554992 -131.231977 0.000000 7058.031360 0.000000 2369.128157
+EDGE_SE2 543 544 0.004143 0.001613 0.643358 365523.202414 1309813.828807 0.000000 4693733.444673 0.000000 925.711464
+EDGE_SE2 544 545 0.011964 0.010101 1.076679 54873.490374 139170.850294 0.000000 353049.492454 0.000000 579.697285
+EDGE_SE2 545 546 -0.062408 -0.034041 0.835070 2157.534535 6151.646423 0.000000 17641.720853 0.000000 742.394487
+EDGE_SE2 546 547 0.004683 0.006620 1.031598 8884.576322 115819.915331 0.000000 1511737.642851 0.000000 605.709415
+EDGE_SE2 547 548 0.010894 0.005062 0.931876 157491.371124 290395.414023 0.000000 535503.600637 0.000000 669.856096
+EDGE_SE2 548 549 0.018521 0.007174 0.814504 46970.071545 98477.220300 0.000000 206526.818200 0.000000 759.318793
+EDGE_SE2 549 550 0.007039 -0.001728 -0.474679 102346.133104 -429334.075047 0.000000 1801229.739954 0.000000 1149.595399
+EDGE_SE2 550 551 0.012919 -0.003649 -0.620137 63414.169645 -176527.986637 0.000000 491503.647693 0.000000 952.437591
+EDGE_SE2 551 552 0.004870 -0.001510 -0.626201 393240.954950 -1165183.372361 0.000000 3452577.879626 0.000000 945.347676
+EDGE_SE2 552 553 0.131013 -0.071366 -0.571551 34.798953 -324.963500 0.000000 4469.148228 0.000000 1012.238963
+EDGE_SE2 553 554 0.656516 -0.001289 -0.033128 11.325592 -6.879883 0.000000 231.796023 0.000000 2342.241894
+EDGE_SE2 554 555 0.640736 0.024110 0.091367 11.781224 12.453936 0.000000 242.565349 0.000000 2098.932021
+EDGE_SE2 555 556 0.644807 0.029102 0.137696 13.068095 21.074909 0.000000 238.068451 0.000000 1931.468129
+EDGE_SE2 556 557 0.641564 -0.010754 -0.042948 11.270029 -6.066916 0.000000 242.724912 0.000000 2298.342233
+EDGE_SE2 557 558 0.615263 0.021826 0.078921 11.588181 10.969921 0.000000 263.357654 0.000000 2147.636202
+EDGE_SE2 558 559 0.005363 -0.000612 -0.410558 293857.680729 -960260.813810 0.000000 3138046.146667 0.000000 1256.487325
+EDGE_SE2 559 560 0.000000 0.000000 -0.505043 102.152456 -164.670704 0.000000 308.958656 0.000000 1103.677058
+EDGE_SE2 560 561 0.009398 0.003440 0.501104 22371.403618 147733.503165 0.000000 976080.093687 0.000000 1109.476905
+EDGE_SE2 561 562 0.177331 0.126693 0.638384 11.791812 37.750509 0.000000 2104.689083 0.000000 931.340765
+EDGE_SE2 562 563 0.597201 -0.094603 -0.194811 11.484023 -9.885231 0.000000 273.150922 0.000000 1751.223531
+EDGE_SE2 563 564 0.639558 0.013847 0.046248 11.252240 5.735744 0.000000 244.222662 0.000000 2283.866567
+EDGE_SE2 564 565 0.614599 -0.011365 -0.051966 11.395132 -8.481100 0.000000 264.363876 0.000000 2259.105962
+EDGE_SE2 565 566 0.005382 -0.000625 0.804171 2155482.804415 1641813.690713 0.000000 1250573.669361 0.000000 768.041369
+EDGE_SE2 566 567 -0.001231 0.000678 0.856086 48423129.554559 10395439.301461 0.000000 2231696.342135 0.000000 725.677769
+EDGE_SE2 567 568 0.583042 0.017568 0.046196 11.184172 4.544849 0.000000 293.831241 0.000000 2284.093607
+EDGE_SE2 568 569 0.628101 -0.010139 -0.052147 11.425095 -8.716657 0.000000 253.098625 0.000000 2258.328765
+EDGE_SE2 569 570 0.639821 -0.001979 -0.004808 11.111796 -0.399705 0.000000 244.274090 0.000000 2476.132272
+EDGE_SE2 570 571 0.348563 -0.003118 -0.043397 12.074353 -27.948587 0.000000 822.042846 0.000000 2296.364589
+EDGE_SE2 571 572 0.037203 -0.034953 -0.237353 9379.952208 16482.424026 0.000000 29008.326343 0.000000 1632.874389
+EDGE_SE2 572 573 0.082599 0.001138 0.282645 1044.389047 3750.080318 0.000000 13621.294688 0.000000 1519.592228
+EDGE_SE2 573 574 0.006029 0.005935 0.955816 43915.035779 243749.664142 0.000000 1353281.899972 0.000000 653.557826
+EDGE_SE2 574 575 0.017352 0.009648 1.009306 58713.654313 106982.648688 0.000000 194982.001569 0.000000 619.224094
+EDGE_SE2 575 576 -0.000693 0.000729 1.024139 92116121.130465 -24932672.587732 0.000000 6748430.711509 0.000000 610.181931
+EDGE_SE2 576 577 0.005808 0.005602 0.968758 61460.098525 300963.429168 0.000000 1474062.832839 0.000000 644.993297
+EDGE_SE2 577 578 0.020578 -0.005874 -0.365770 1686.236926 -19051.115635 0.000000 216678.422748 0.000000 1340.246481
+EDGE_SE2 578 579 0.649778 -0.007064 0.014101 11.251830 5.633981 0.000000 236.679123 0.000000 2430.958734
+EDGE_SE2 579 580 0.646533 0.021127 0.074055 11.501231 9.420338 0.000000 238.586536 0.000000 2167.139990
+EDGE_SE2 580 581 0.641277 0.007721 0.041304 11.309760 6.786133 0.000000 242.935131 0.000000 2305.605160
+EDGE_SE2 581 582 0.642222 0.008953 0.042003 11.293216 6.487457 0.000000 242.225126 0.000000 2302.512889
+EDGE_SE2 582 583 0.324533 0.007424 0.078126 13.971366 51.714099 0.000000 946.114403 0.000000 2150.804664
+EDGE_SE2 583 584 0.003585 0.000066 0.840201 4172109.666193 3878928.313892 0.000000 3606370.037121 0.000000 738.260001
+EDGE_SE2 584 585 0.609333 0.022255 0.117010 12.778611 20.669000 0.000000 267.307574 0.000000 2003.668573
+EDGE_SE2 585 586 0.610182 0.017652 0.096276 12.276387 17.274488 0.000000 267.194725 0.000000 2080.176547
+EDGE_SE2 586 587 0.632351 0.024309 0.024257 11.158994 -3.379740 0.000000 249.665755 0.000000 2382.989492
+EDGE_SE2 587 588 0.643770 -0.006740 0.003322 11.154886 3.173805 0.000000 241.219104 0.000000 2483.472403
+EDGE_SE2 588 589 0.633840 0.040950 0.080270 11.169866 3.729294 0.000000 247.815430 0.000000 2142.275779
+EDGE_SE2 589 590 0.644706 0.014870 0.073779 11.700561 11.612184 0.000000 239.871719 0.000000 2168.254200
+EDGE_SE2 590 591 0.632424 0.012303 0.002621 11.178752 -4.018640 0.000000 249.862554 0.000000 2486.946343
+EDGE_SE2 591 592 0.642169 0.006914 0.001997 11.128903 -2.028750 0.000000 242.448415 0.000000 2490.044831
+EDGE_SE2 592 593 0.271993 0.001273 0.212505 68.183858 270.652782 0.000000 1294.612122 0.000000 1700.485497
+EDGE_SE2 593 594 0.014453 0.008841 0.993097 64316.365031 135154.721370 0.000000 284074.972077 0.000000 629.336815
+EDGE_SE2 594 595 0.571176 0.080832 0.240324 13.980407 28.672593 0.000000 297.633480 0.000000 1625.061173
+EDGE_SE2 595 596 0.575835 0.004878 -0.017875 11.312665 -7.648565 0.000000 301.358130 0.000000 2412.965503
+EDGE_SE2 596 597 0.635351 -0.013108 -0.034135 11.154253 -3.193993 0.000000 247.578146 0.000000 2337.682549
+EDGE_SE2 597 598 0.604127 -0.006451 -0.039602 11.330957 -7.598611 0.000000 273.744081 0.000000 2313.160651
+EDGE_SE2 598 599 0.385673 -0.010715 -0.063459 11.952011 -23.555254 0.000000 670.939617 0.000000 2210.540655
+EDGE_SE2 599 600 0.008688 0.002526 0.814757 314076.796383 533827.575685 0.000000 907375.060518 0.000000 759.107091
+EDGE_SE2 600 601 0.021686 0.011399 1.028615 44738.476040 73830.093373 0.000000 121880.188267 0.000000 607.492253
+EDGE_SE2 601 602 0.018101 0.007667 1.024411 88285.368598 122674.329555 0.000000 170491.062574 0.000000 610.017974
+EDGE_SE2 602 603 0.186319 0.162792 0.780432 17.405089 100.856712 0.000000 1627.271409 0.000000 788.658931
+EDGE_SE2 603 604 0.621077 -0.063008 -0.240492 15.850028 -33.777361 0.000000 251.864479 0.000000 1624.621039
+EDGE_SE2 604 605 0.633484 0.018906 0.082620 11.773196 12.531662 0.000000 248.305264 0.000000 2132.985568
+EDGE_SE2 605 606 0.635159 0.014918 0.042086 11.193000 4.401211 0.000000 247.658010 0.000000 2302.146123
+EDGE_SE2 606 607 0.573078 -0.057501 -0.081034 11.215573 5.506259 0.000000 301.350193 0.000000 2139.248825
+EDGE_SE2 607 608 0.372357 0.012526 0.044458 11.194332 7.682633 0.000000 720.342546 0.000000 2291.701491
+EDGE_SE2 608 609 0.009981 0.001237 0.336295 44194.195786 204270.386082 0.000000 944408.518792 0.000000 1400.022844
+EDGE_SE2 609 610 0.008024 0.008992 0.932617 5618.242041 61880.517104 0.000000 682926.927594 0.000000 669.342525
+EDGE_SE2 610 611 0.619179 0.006175 0.002964 11.123375 -1.749910 0.000000 260.797662 0.000000 2485.245630
+EDGE_SE2 611 612 0.495865 -0.011645 0.002777 11.383631 10.376429 0.000000 406.201910 0.000000 2486.172625
+EDGE_SE2 612 613 -0.032580 0.001507 0.463705 22407.672171 40045.920128 0.000000 71614.770023 0.000000 1166.898001
+EDGE_SE2 613 614 0.006074 0.002811 1.037837 720992.332387 1043867.597380 0.000000 1511367.480327 0.000000 602.006419
+EDGE_SE2 614 615 0.468918 0.167392 0.304515 11.688040 -15.032631 0.000000 402.805589 0.000000 1469.067849
+EDGE_SE2 615 616 0.634148 0.014484 -0.051156 12.408628 -17.503753 0.000000 247.240026 0.000000 2262.588948
+EDGE_SE2 616 617 0.620915 -0.099361 -0.217030 11.933466 -14.077035 0.000000 252.081317 0.000000 1687.863964
+EDGE_SE2 617 618 0.637519 0.006833 0.010118 11.111196 -0.140914 0.000000 246.016254 0.000000 2450.167576
+EDGE_SE2 618 619 0.602001 -0.001093 -0.001468 11.111143 0.091989 0.000000 275.933653 0.000000 2492.676131
+EDGE_SE2 619 620 0.611116 -0.021079 -0.096329 12.090448 -15.813910 0.000000 266.467179 0.000000 2079.975428
+EDGE_SE2 620 621 -0.351742 0.001000 -0.051606 13.005075 -38.809484 0.000000 806.361703 0.000000 2260.652962
+EDGE_SE2 621 622 -0.288473 0.005647 -0.075042 14.769187 -65.879798 0.000000 1197.567688 0.000000 2163.162499
+EDGE_SE2 622 623 -0.003587 0.000519 -0.537149 1119299.663768 -2695881.271885 0.000000 6493221.297933 0.000000 1058.054588
+EDGE_SE2 623 624 -0.002684 0.001648 -0.642690 84963.761375 -921398.117942 0.000000 9993513.245668 0.000000 926.464498
+EDGE_SE2 624 625 0.007502 -0.002176 -0.658633 221323.684950 -560152.893180 0.000000 1417785.340096 0.000000 908.739498
+EDGE_SE2 625 626 0.007582 -0.000720 -0.618128 430777.189603 -746427.081854 0.000000 1293412.370737 0.000000 954.803710
+EDGE_SE2 626 627 0.339972 -0.139061 -0.410806 11.481721 -16.444927 0.000000 740.815480 0.000000 1256.045618
+EDGE_SE2 627 628 0.641810 -0.041240 -0.100917 11.422475 -8.468830 0.000000 241.456222 0.000000 2062.675227
+EDGE_SE2 628 629 0.640763 0.030371 0.071050 11.241212 5.491249 0.000000 242.883687 0.000000 2179.317557
+EDGE_SE2 629 630 0.608678 0.024217 0.085089 11.641507 11.694459 0.000000 268.956806 0.000000 2123.289866
+EDGE_SE2 630 631 0.520687 0.012252 0.020220 11.115021 -1.182335 0.000000 368.639644 0.000000 2401.885734
+EDGE_SE2 631 632 0.003617 -0.000095 0.676209 3189142.029325 3767706.315238 0.000000 4451258.564395 0.000000 889.781790
+EDGE_SE2 632 633 0.052581 0.076324 1.075605 146.388666 1246.996416 0.000000 11505.997044 0.000000 580.297357
+EDGE_SE2 633 634 0.651291 -0.000853 0.025227 11.269271 5.958489 0.000000 235.590568 0.000000 2378.482380
+EDGE_SE2 634 635 0.638650 -0.043082 -0.137291 12.248607 -16.238485 0.000000 242.925867 0.000000 1932.844002
+EDGE_SE2 635 636 0.635527 0.004328 -0.019084 11.269630 -6.120407 0.000000 247.419146 0.000000 2407.243610
+EDGE_SE2 636 637 0.632517 -0.030952 -0.100684 11.749524 -12.316243 0.000000 248.715635 0.000000 2063.548601
+EDGE_SE2 637 638 0.419086 -0.009115 -0.030747 11.156304 -5.021448 0.000000 569.055296 0.000000 2353.075434
+EDGE_SE2 638 639 0.640680 0.028288 0.078765 11.389438 8.031492 0.000000 242.870396 0.000000 2148.257386
+EDGE_SE2 639 640 0.645185 -0.028949 -0.069702 11.252424 -5.682397 0.000000 239.608542 0.000000 2184.813613
+EDGE_SE2 640 641 0.631149 0.010125 -0.010170 11.275857 -6.284012 0.000000 250.806675 0.000000 2449.915330
+EDGE_SE2 641 642 0.608456 -0.016443 -0.047551 11.220217 -5.312718 0.000000 269.804578 0.000000 2278.188510
+EDGE_SE2 642 643 0.501922 -0.014902 -0.065028 11.592531 -13.614212 0.000000 396.111379 0.000000 2204.032313
+EDGE_SE2 643 644 0.006192 0.003634 0.763605 103362.922493 435664.745636 0.000000 1836493.394795 0.000000 803.780315
+EDGE_SE2 644 645 0.147583 0.161030 0.956903 45.062660 263.875747 0.000000 2061.986889 0.000000 652.831965
+EDGE_SE2 645 646 0.624864 0.078137 0.297396 18.253618 40.874666 0.000000 245.025960 0.000000 1485.234058
+EDGE_SE2 646 647 0.626416 0.074352 0.291155 18.229469 40.732090 0.000000 244.184966 0.000000 1499.626982
+EDGE_SE2 647 648 0.630437 0.066336 0.168411 12.070691 15.073373 0.000000 247.888334 0.000000 1831.254626
+EDGE_SE2 648 649 0.592663 -0.072497 -0.334526 23.127883 -55.612924 0.000000 268.484510 0.000000 1403.737590
+EDGE_SE2 649 650 0.621511 -0.143009 -0.254374 11.297892 -6.619122 0.000000 245.678334 0.000000 1588.861060
+EDGE_SE2 650 651 0.144853 0.010732 0.805829 2122.876396 2350.861156 0.000000 2628.138776 0.000000 766.631681
+EDGE_SE2 651 652 0.002718 0.001656 1.033599 2156297.352241 4079208.548390 0.000000 7716956.136248 0.000000 604.518184
+EDGE_SE2 652 653 0.014957 0.011986 1.038848 34378.938116 90407.858801 0.000000 237837.637992 0.000000 601.409535
+EDGE_SE2 653 654 0.267736 0.151078 0.517447 11.125502 3.881714 0.000000 1058.107188 0.000000 1085.707770
+EDGE_SE2 654 655 0.563434 -0.005218 -0.003312 11.121867 1.807836 0.000000 314.964252 0.000000 2483.521908
+EDGE_SE2 655 656 0.610635 -0.014726 -0.011084 11.154711 3.346600 0.000000 267.986619 0.000000 2445.487982
+EDGE_SE2 656 657 0.631799 0.103933 0.278849 14.219359 26.720114 0.000000 240.811095 0.000000 1528.626076
+EDGE_SE2 657 658 0.640227 0.007103 -0.006984 11.187191 -4.208049 0.000000 243.861599 0.000000 2465.442445
+EDGE_SE2 658 659 0.497774 -0.026439 -0.071049 11.237681 -7.036752 0.000000 402.323496 0.000000 2179.321626
+EDGE_SE2 659 660 0.006409 -0.000096 0.600351 810833.659716 1147194.412851 0.000000 1623122.139710 0.000000 976.134174
+EDGE_SE2 660 661 0.169432 0.128488 0.653648 11.162367 10.620021 0.000000 2211.525163 0.000000 914.226633
+EDGE_SE2 661 662 0.629749 0.003998 0.069631 12.075080 15.212434 0.000000 251.179162 0.000000 2185.103670
+EDGE_SE2 662 663 0.621897 0.037784 0.101008 11.511766 9.929781 0.000000 257.209513 0.000000 2062.334274
+EDGE_SE2 663 664 0.007280 -0.002392 0.538314 970988.716591 843174.347297 0.000000 732204.084386 0.000000 1056.452618
+EDGE_SE2 664 665 0.026579 0.029587 0.878851 111.857316 2521.446990 0.000000 63117.159733 0.000000 708.199031
+EDGE_SE2 665 666 0.623804 0.018831 0.034452 11.115596 1.049644 0.000000 256.744183 0.000000 2336.250038
+EDGE_SE2 666 667 0.580478 0.005759 0.002114 11.128518 -2.229713 0.000000 296.729354 0.000000 2489.463423
+EDGE_SE2 667 668 0.608507 -0.000467 0.023179 11.259577 6.198692 0.000000 269.917040 0.000000 2388.013473
+EDGE_SE2 668 669 0.638606 0.001692 -0.027742 11.327262 -7.110068 0.000000 244.989751 0.000000 2366.855797
+EDGE_SE2 669 670 0.636315 -0.034673 -0.062258 11.125493 -1.838895 0.000000 246.230714 0.000000 2215.542002
+EDGE_SE2 670 671 0.308072 0.001150 0.052261 13.564460 50.513802 0.000000 1051.177078 0.000000 2257.839465
+EDGE_SE2 671 672 -0.576602 0.036531 -0.092061 11.350145 -8.300360 0.000000 299.337680 0.000000 2096.265145
+EDGE_SE2 672 673 -0.262392 0.011580 -0.133741 22.638322 -128.254010 0.000000 1438.090461 0.000000 1944.967298
+EDGE_SE2 673 674 -0.005814 0.002674 -0.655099 120542.083833 -528941.427411 0.000000 2321232.182459 0.000000 912.624358
+EDGE_SE2 674 675 -0.014637 0.005942 -0.615221 20765.078980 -88798.929746 0.000000 379950.502646 0.000000 958.243990
+EDGE_SE2 675 676 -0.006630 0.003741 -0.630060 23265.609241 -198963.775781 0.000000 1702330.544222 0.000000 940.876947
+EDGE_SE2 676 677 -0.012856 0.004015 -0.622499 54491.338930 -164518.778220 0.000000 496823.064188 0.000000 949.666532
+EDGE_SE2 677 678 0.191689 -0.090627 -0.451238 11.315076 -21.245540 0.000000 2224.105339 0.000000 1187.032313
+EDGE_SE2 678 679 0.570835 0.011396 0.059784 11.579724 11.761290 0.000000 306.296841 0.000000 2225.898166
+EDGE_SE2 679 680 0.434701 0.056384 0.340338 33.525701 104.470312 0.000000 498.028172 0.000000 1391.589518
+EDGE_SE2 680 681 0.616588 -0.017915 -0.025786 11.113788 0.820773 0.000000 262.808564 0.000000 2375.890788
+EDGE_SE2 681 682 0.634780 0.014947 0.049632 11.272332 6.178273 0.000000 247.873967 0.000000 2269.163993
+EDGE_SE2 682 683 0.300050 0.004977 0.161644 34.081549 157.239703 0.000000 1087.465169 0.000000 1852.652221
+EDGE_SE2 683 684 0.008066 0.002610 1.069340 655223.236656 694424.027218 0.000000 735993.720066 0.000000 583.816417
+EDGE_SE2 684 685 0.408559 0.177472 0.439476 11.545242 14.621378 0.000000 503.554260 0.000000 1206.510628
+EDGE_SE2 685 686 0.481253 -0.056338 -0.146676 11.487851 -12.495538 0.000000 425.557060 0.000000 1901.334651
+EDGE_SE2 686 687 0.633778 -0.013418 -0.036773 11.168993 -3.709053 0.000000 248.788111 0.000000 2325.801528
+EDGE_SE2 687 688 0.633546 -0.023306 -0.013253 11.242546 5.587827 0.000000 248.672293 0.000000 2435.029417
+EDGE_SE2 688 689 0.601923 0.011148 0.026350 11.127352 2.073709 0.000000 275.894586 0.000000 2373.280306
+EDGE_SE2 689 690 0.577060 0.031776 0.072952 11.203899 5.171117 0.000000 299.300801 0.000000 2171.597942
+EDGE_SE2 690 691 0.431081 -0.000968 -0.029004 11.488376 -14.095403 0.000000 537.744126 0.000000 2361.053797
+EDGE_SE2 691 692 -0.008991 -0.001137 0.532009 190083.391915 441924.473409 0.000000 1027500.439761 0.000000 1065.166196
+EDGE_SE2 692 693 -0.002490 -0.004336 1.036147 719.063258 -53205.166853 0.000000 3998572.017505 0.000000 603.006163
+EDGE_SE2 693 694 -0.004998 -0.000127 0.832038 2085335.472274 1998610.421428 0.000000 1915513.414270 0.000000 744.853827
+EDGE_SE2 694 695 0.001511 0.001312 0.796919 166502.359918 2031923.976353 0.000000 24798401.868961 0.000000 774.253197
+EDGE_SE2 695 696 0.013256 0.002978 1.021557 279104.028874 270742.205141 0.000000 262652.464508 0.000000 611.741616
+EDGE_SE2 696 697 0.014932 -0.001676 -0.254525 8971.193925 -62353.454280 0.000000 433930.455572 0.000000 1588.478599
+EDGE_SE2 697 698 0.334592 -0.212289 -0.657753 16.435194 -57.473689 0.000000 631.541865 0.000000 909.704543
+EDGE_SE2 698 699 0.645635 0.022320 0.112426 12.493854 17.721303 0.000000 238.228242 0.000000 2020.215724
+EDGE_SE2 699 700 0.637453 0.017479 0.051850 11.251293 5.735412 0.000000 245.770774 0.000000 2259.604267
+EDGE_SE2 700 701 0.580454 0.032375 0.057254 11.111784 0.437751 0.000000 295.879739 0.000000 2236.564024
+EDGE_SE2 701 702 0.576635 -0.068380 -0.117543 11.111180 0.139782 0.000000 296.573785 0.000000 2001.757773
+EDGE_SE2 702 703 0.620013 -0.001990 0.031996 11.419637 8.759800 0.000000 259.823358 0.000000 2347.383139
+EDGE_SE2 703 704 0.636789 0.025712 0.015764 11.253257 -5.779092 0.000000 246.065659 0.000000 2423.005361
+EDGE_SE2 704 705 0.643209 0.030107 0.064485 11.183283 4.074239 0.000000 241.110228 0.000000 2206.281466
+EDGE_SE2 705 706 0.514363 -0.039200 -0.277636 25.728836 -71.533878 0.000000 361.172137 0.000000 1531.530774
+EDGE_SE2 706 707 0.003881 -0.001622 -0.533536 106334.972814 -767757.982233 0.000000 5543943.675681 0.000000 1063.046000
+EDGE_SE2 707 708 -0.003691 0.001823 -0.654541 223240.622476 -1125745.646018 0.000000 5677142.471470 0.000000 913.240034
+EDGE_SE2 708 709 -0.067573 0.007248 -0.341732 1183.126036 -4897.853094 0.000000 20479.250565 0.000000 1388.700057
+EDGE_SE2 709 710 -0.014148 0.002189 -0.575257 81786.222098 -182245.919313 0.000000 406168.616806 0.000000 1007.481714
+EDGE_SE2 710 711 0.000644 0.000757 -0.611741 100340028.914478 -9326915.500645 0.000000 866976.800978 0.000000 962.386453
+EDGE_SE2 711 712 -0.004894 0.001455 -0.574644 304805.524713 -1037473.284048 0.000000 3531410.530133 0.000000 1008.266280
+EDGE_SE2 712 713 0.477793 -0.132293 -0.294292 11.342379 -9.563968 0.000000 406.624099 0.000000 1492.366443
+EDGE_SE2 713 714 0.567602 -0.077796 -0.205164 12.504613 -20.177539 0.000000 303.276539 0.000000 1721.264882
+EDGE_SE2 714 715 0.633486 0.028573 0.105231 11.969833 14.257268 0.000000 247.822982 0.000000 2046.604352
+EDGE_SE2 715 716 0.639776 -0.022007 -0.136206 13.517556 -23.552031 0.000000 241.616372 0.000000 1936.537236
+EDGE_SE2 716 717 0.632432 0.018685 0.086524 11.885459 13.573115 0.000000 249.026579 0.000000 2117.685003
+EDGE_SE2 717 718 0.776383 -0.078919 -0.173172 11.900522 -10.964942 0.000000 163.414455 0.000000 1816.421486
+EDGE_SE2 718 719 0.636837 0.028128 0.076417 11.355832 7.579234 0.000000 245.847108 0.000000 2157.639641
+EDGE_SE2 719 720 0.632529 -0.017060 -0.057232 11.329664 -7.218698 0.000000 249.541537 0.000000 2236.657107
+EDGE_SE2 720 721 0.638105 0.018029 0.070335 11.525887 9.849065 0.000000 244.982458 0.000000 2182.230164
+EDGE_SE2 721 722 0.025289 0.000135 0.068811 640.196727 9897.678857 0.000000 155735.617178 0.000000 2188.457812
+EDGE_SE2 722 723 0.006445 0.007867 1.098357 43580.586864 200575.333708 0.000000 923374.631033 0.000000 567.781519
+EDGE_SE2 723 724 0.010463 0.006590 1.077175 158723.565692 280363.009735 0.000000 495267.878673 0.000000 579.420471
+EDGE_SE2 724 725 0.010678 0.005468 0.639413 19006.567647 113303.006550 0.000000 675834.367551 0.000000 930.171994
+EDGE_SE2 725 726 0.290588 0.137540 0.458060 11.355500 15.286330 0.000000 967.259181 0.000000 1175.950976
+EDGE_SE2 726 727 0.635716 0.023142 0.032574 11.114541 -0.899732 0.000000 247.111115 0.000000 2344.755903
+EDGE_SE2 727 728 0.637440 -0.010740 0.003027 11.203891 4.667737 0.000000 245.942991 0.000000 2484.933444
+EDGE_SE2 728 729 0.638658 0.024646 0.059374 11.212224 4.859951 0.000000 244.701967 0.000000 2227.621438
+EDGE_SE2 729 730 0.629725 0.021040 0.039078 11.118875 1.367234 0.000000 251.883563 0.000000 2315.494262
+EDGE_SE2 730 731 0.635128 0.000033 0.013336 11.152896 3.145232 0.000000 247.858605 0.000000 2434.630538
+EDGE_SE2 731 732 0.123756 0.004174 0.448902 1070.432039 2403.087812 0.000000 5462.557297 0.000000 1190.863501
+EDGE_SE2 732 733 0.000083 0.001424 1.000990 11773189.473890 -20977730.743166 0.000000 37378633.397513 0.000000 624.381709
+EDGE_SE2 733 734 0.552572 0.038413 0.079326 11.142093 3.122929 0.000000 325.902343 0.000000 2146.024772
+EDGE_SE2 734 735 0.600091 -0.007820 -0.030980 11.196982 -4.783337 0.000000 277.560623 0.000000 2352.011970
+EDGE_SE2 735 736 0.005111 -0.000077 0.602090 1281626.650843 1806077.209424 0.000000 2545169.768506 0.000000 974.015847
+EDGE_SE2 736 737 0.008677 0.008287 0.804006 1211.768495 28855.042050 0.000000 693475.760746 0.000000 768.181871
+EDGE_SE2 737 738 0.598858 0.011099 0.020076 11.111750 0.413426 0.000000 278.741652 0.000000 2402.563911
+EDGE_SE2 738 739 0.625793 -0.054407 -0.056575 11.331296 7.301220 0.000000 253.215672 0.000000 2239.439570
+EDGE_SE2 739 740 0.522300 0.024647 0.064307 11.215445 6.082008 0.000000 365.653135 0.000000 2207.019506
+EDGE_SE2 740 741 -0.000981 -0.000074 -0.367127 18919361.341981 -39981559.645604 0.000000 84491555.069462 0.000000 1337.587765
+EDGE_SE2 741 742 0.011219 -0.001990 -0.650273 160936.661861 -313150.446277 0.000000 609381.105788 0.000000 917.969856
+EDGE_SE2 742 743 0.004918 -0.001325 -0.614408 456134.364729 -1245052.232453 0.000000 3398555.362562 0.000000 959.208992
+EDGE_SE2 743 744 0.009459 -0.002723 -0.537185 66620.250624 -253582.580605 0.000000 965406.035238 0.000000 1058.005031
+EDGE_SE2 744 745 0.002047 -0.000908 -0.591149 593780.161881 -3389363.396311 0.000000 19347237.473549 0.000000 987.457262
+EDGE_SE2 745 746 0.494445 -0.175533 -0.472825 17.183290 -45.841209 0.000000 357.183969 0.000000 1152.491455
+EDGE_SE2 746 747 0.638469 -0.005433 -0.034207 11.265722 -6.015279 0.000000 245.140841 0.000000 2337.357068
+EDGE_SE2 747 748 0.577733 -0.023010 -0.067174 11.326766 -7.878192 0.000000 298.912675 0.000000 2195.176966
+EDGE_SE2 748 749 0.069701 0.001911 0.431306 3186.109937 7428.826456 0.000000 17392.995499 0.000000 1220.323642
+EDGE_SE2 749 750 0.003545 0.004632 0.930924 530.021459 39050.161440 0.000000 2938698.139852 0.000000 670.516775
+EDGE_SE2 750 751 0.221430 0.155717 0.642978 12.335877 40.697289 0.000000 1363.426091 0.000000 926.139724
+EDGE_SE2 751 752 0.622533 -0.037077 -0.102200 11.559653 -10.494975 0.000000 256.672582 0.000000 2057.875967
+EDGE_SE2 752 753 0.636978 0.006588 0.064190 11.792803 12.647310 0.000000 245.754530 0.000000 2207.504825
+EDGE_SE2 753 754 0.633682 -0.063409 -0.161022 11.994454 -14.394628 0.000000 245.680720 0.000000 1854.637814
+EDGE_SE2 754 755 0.634065 0.020125 0.076284 11.582011 10.562020 0.000000 248.011279 0.000000 2158.172928
+EDGE_SE2 755 756 0.630931 -0.052093 -0.191444 13.935694 -25.795248 0.000000 246.683906 0.000000 1761.135371
+EDGE_SE2 756 757 0.634731 0.023338 0.098895 12.024248 14.675298 0.000000 246.962348 0.000000 2070.272980
+EDGE_SE2 757 758 0.593380 0.045763 0.126480 11.775379 13.406035 0.000000 281.667065 0.000000 1970.121623
+EDGE_SE2 758 759 0.549299 -0.065716 -0.139191 11.238871 -6.348958 0.000000 326.618479 0.000000 1926.401990
+EDGE_SE2 759 760 0.597230 0.041521 0.114150 11.646967 11.969500 0.000000 278.475751 0.000000 2013.968527
+EDGE_SE2 760 761 0.024133 -0.000801 0.183513 7939.377412 36011.249548 0.000000 163579.039427 0.000000 1784.818025
+EDGE_SE2 761 762 0.000826 0.001155 1.009551 175055.866129 2941983.942252 0.000000 49446048.586526 0.000000 619.072925
+EDGE_SE2 762 763 0.580729 0.162376 0.292110 11.211099 5.135900 0.000000 274.918098 0.000000 1497.411049
+EDGE_SE2 763 764 0.445705 -0.005172 -0.027993 11.243315 -8.065663 0.000000 503.190215 0.000000 2365.700131
+EDGE_SE2 764 765 0.008361 0.001719 0.638276 244331.555302 525026.230585 0.000000 1128252.931867 0.000000 931.463562
+EDGE_SE2 765 766 0.005344 0.005700 0.998613 53037.087612 289905.348468 0.000000 1584991.089178 0.000000 625.867778
+EDGE_SE2 766 767 0.002645 0.001415 0.929266 1998232.117440 4267585.657123 0.000000 9114261.878773 0.000000 671.669747
+EDGE_SE2 767 768 0.005861 0.004878 0.721092 1261.041135 46349.790224 0.000000 1718749.770688 0.000000 843.979381
+EDGE_SE2 768 769 0.614146 0.107525 0.156299 11.182444 -4.189539 0.000000 257.172044 0.000000 1869.819603
+EDGE_SE2 769 770 0.636280 -0.020581 -0.067664 11.405109 -8.318026 0.000000 246.451563 0.000000 2193.162494
+EDGE_SE2 770 771 0.070000 0.001891 0.559330 5261.360007 8913.246458 0.000000 15142.958000 0.000000 1028.167661
+EDGE_SE2 771 772 0.006744 0.005112 0.865896 64935.054362 294012.600872 0.000000 1331467.660768 0.000000 718.067286
+EDGE_SE2 772 773 0.581158 0.026914 0.085198 11.541618 11.055471 0.000000 295.017264 0.000000 2122.863350
+EDGE_SE2 773 774 0.551019 0.013319 0.021516 11.113346 -0.843063 0.000000 329.161850 0.000000 2395.795043
+EDGE_SE2 774 775 0.004023 0.000830 0.842994 2110367.484852 2837367.218934 0.000000 3814842.025573 0.000000 736.024077
+EDGE_SE2 775 776 0.192558 0.126940 0.615944 13.158809 61.827681 0.000000 1877.920658 0.000000 957.386713
+EDGE_SE2 776 777 0.634282 0.011394 0.058423 11.499517 9.594027 0.000000 248.093510 0.000000 2231.626302
+EDGE_SE2 777 778 0.632295 0.006026 -0.021506 11.341246 -7.412667 0.000000 249.873975 0.000000 2395.841950
+EDGE_SE2 778 779 0.635747 0.009144 0.017394 11.113255 0.711673 0.000000 247.364613 0.000000 2415.247629
+EDGE_SE2 779 780 0.227263 -0.012780 -0.131130 21.872372 -143.298917 0.000000 1919.305655 0.000000 1953.956841
+EDGE_SE2 780 781 0.009670 -0.001829 -0.575170 148004.400196 -361794.734360 0.000000 884479.796277 0.000000 1007.593008
+EDGE_SE2 781 782 0.270298 -0.114336 -0.431075 12.208626 -35.507762 0.000000 1159.889369 0.000000 1220.717636
+EDGE_SE2 782 783 0.611405 -0.011479 -0.001409 11.188373 4.449352 0.000000 267.339350 0.000000 2492.969862
+EDGE_SE2 783 784 0.240113 0.001039 -0.022196 12.323249 -45.688698 0.000000 1733.239839 0.000000 2392.608572
+EDGE_SE2 784 785 0.007959 -0.002926 -0.554001 55828.680061 -272963.055421 0.000000 1334874.506740 0.000000 1035.230954
+EDGE_SE2 785 786 0.004434 -0.000587 -0.590466 980656.281246 -1985068.949325 0.000000 4018282.809762 0.000000 988.305540
+EDGE_SE2 786 787 -0.002001 0.000044 -0.492560 5130982.209484 -10089392.987608 0.000000 19839501.318078 0.000000 1122.215884
+EDGE_SE2 787 788 0.007208 -0.003016 -0.631388 88847.369552 -370943.890957 0.000000 1548921.124356 0.000000 939.345765
+EDGE_SE2 788 789 0.007538 -0.002876 -0.554007 54527.813069 -284219.801981 0.000000 1481775.284964 0.000000 1035.223369
+EDGE_SE2 789 790 0.500376 -0.029812 -0.068057 11.139386 -3.307267 0.000000 397.957897 0.000000 2191.548808
+EDGE_SE2 790 791 0.628826 0.029153 0.097815 11.750061 12.398882 0.000000 251.712715 0.000000 2074.348338
+EDGE_SE2 791 792 0.315704 0.029420 0.702590 333.591596 461.723980 0.000000 672.202381 0.000000 862.422051
+EDGE_SE2 792 793 0.615391 0.019005 0.041490 11.139594 2.682653 0.000000 263.776793 0.000000 2304.781716
+EDGE_SE2 793 794 0.637735 0.016326 0.067824 11.529260 9.895724 0.000000 245.298956 0.000000 2192.505307
+EDGE_SE2 794 795 -0.033087 -0.024410 0.423241 2638.528642 -12185.315173 0.000000 56523.600693 0.000000 1234.193106
+EDGE_SE2 795 796 -0.015774 0.000648 0.650956 163376.535826 197117.295726 0.000000 237853.533044 0.000000 917.210485
+EDGE_SE2 796 797 0.294705 0.074097 0.255423 11.199896 9.754709 0.000000 1082.852214 0.000000 1586.206944
+EDGE_SE2 797 798 0.626641 0.006060 0.046881 11.448159 9.053531 0.000000 254.300351 0.000000 2281.105507
+EDGE_SE2 798 799 0.635666 0.023992 0.062363 11.254358 5.812774 0.000000 246.986103 0.000000 2215.104071
+EDGE_SE2 799 800 0.634468 0.014510 0.069489 11.626291 11.041861 0.000000 247.771504 0.000000 2185.683957
+EDGE_SE2 800 801 0.637847 0.031241 0.082897 11.380932 7.942930 0.000000 244.933506 0.000000 2131.894492
+EDGE_SE2 801 802 0.632634 0.019958 0.054891 11.241159 5.567715 0.000000 249.480486 0.000000 2246.595241
+EDGE_SE2 802 803 0.630127 -0.088612 -0.168062 11.300661 -6.683601 0.000000 246.777787 0.000000 1832.349094
+EDGE_SE2 803 804 0.635077 0.012853 0.053211 11.368430 7.800535 0.000000 247.581479 0.000000 2253.768144
+EDGE_SE2 804 805 0.636519 0.031282 0.073549 11.251547 5.744442 0.000000 246.083247 0.000000 2169.183365
+EDGE_SE2 805 806 0.606343 0.012170 0.038909 11.203672 4.912129 0.000000 271.793935 0.000000 2316.247649
+EDGE_SE2 806 807 0.189729 0.005119 0.292220 201.113736 699.449492 0.000000 2585.968127 0.000000 1497.155415
+EDGE_SE2 807 808 0.003371 0.007327 0.958098 50103.576561 -272947.437303 0.000000 1487266.786417 0.000000 652.035379
+EDGE_SE2 808 809 0.587431 0.097914 0.147917 11.191667 -4.670314 0.000000 281.877711 0.000000 1897.225851
+EDGE_SE2 809 810 0.627956 -0.080646 -0.136964 11.131446 -2.201546 0.000000 249.460063 0.000000 1933.955965
+EDGE_SE2 810 811 0.612576 0.015533 -0.000815 11.285797 -6.674619 0.000000 266.143624 0.000000 2495.929976
+EDGE_SE2 811 812 0.006046 0.000091 0.739463 1201081.516913 1357305.749329 0.000000 1533875.311129 0.000000 826.246472
+EDGE_SE2 812 813 0.018109 0.013231 0.985482 23964.289238 64716.524103 0.000000 174861.749709 0.000000 634.173515
+EDGE_SE2 813 814 0.002006 0.002998 1.002590 3587.558087 165756.923868 0.000000 7682316.480714 0.000000 623.384389
+EDGE_SE2 814 815 0.020425 0.007022 0.928829 67887.614244 99709.570495 0.000000 146482.982663 0.000000 671.974131
+EDGE_SE2 815 816 0.008370 0.002024 0.688367 256339.335199 529144.216869 0.000000 1092335.622944 0.000000 877.013540
+EDGE_SE2 816 817 0.011362 -0.004578 -0.661788 50470.023799 -176289.897436 0.000000 615920.695413 0.000000 905.292186
+EDGE_SE2 817 818 0.201346 -0.091729 -0.483386 17.453139 -113.332496 0.000000 2036.370991 0.000000 1136.139494
+EDGE_SE2 818 819 0.600994 -0.000021 0.016657 11.185144 4.434946 0.000000 276.785971 0.000000 2418.750645
+EDGE_SE2 819 820 0.604107 -0.012016 -0.038590 11.203011 -4.913481 0.000000 273.813863 0.000000 2317.670726
+EDGE_SE2 820 821 0.557707 0.002574 0.018330 11.169482 4.256080 0.000000 321.439373 0.000000 2410.809711
+EDGE_SE2 821 822 0.002019 0.000160 0.773476 9984938.759006 11985389.451377 0.000000 14386651.191718 0.000000 794.857685
+EDGE_SE2 822 823 0.012515 0.017002 0.933412 12.904840 -634.367588 0.000000 224360.656810 0.000000 668.792184
+EDGE_SE2 823 824 0.631778 0.009322 -0.078655 13.193602 -22.229505 0.000000 248.399474 0.000000 2148.695562
+EDGE_SE2 824 825 0.640608 -0.019581 -0.029178 11.111552 0.320195 0.000000 243.449875 0.000000 2360.255512
+EDGE_SE2 825 826 0.635727 0.086901 0.163404 11.286990 6.382404 0.000000 242.719295 0.000000 1847.051069
+EDGE_SE2 826 827 0.633058 -0.024805 -0.048406 11.131451 -2.200226 0.000000 249.121319 0.000000 2274.474191
+EDGE_SE2 827 828 0.640515 0.016631 0.035640 11.132900 2.250508 0.000000 243.562272 0.000000 2330.893209
+EDGE_SE2 828 829 0.604311 -0.016371 -0.038614 11.146008 -3.026498 0.000000 273.593060 0.000000 2317.563615
+EDGE_SE2 829 830 0.611353 -0.005562 -0.007256 11.111980 0.472139 0.000000 267.533817 0.000000 2464.111086
+EDGE_SE2 830 831 0.582292 -0.023325 -0.045648 11.120035 -1.590099 0.000000 294.448496 0.000000 2286.488316
+EDGE_SE2 831 832 0.567969 0.005415 -0.002512 11.154466 -3.599292 0.000000 309.920273 0.000000 2487.487168
+EDGE_SE2 832 833 0.256920 0.000340 0.139017 39.444586 204.467263 0.000000 1486.640047 0.000000 1926.990602
+EDGE_SE2 833 834 0.004768 0.001527 1.059143 1850884.389821 1989766.154557 0.000000 2139092.913935 0.000000 589.612746
+EDGE_SE2 834 835 0.011746 0.005469 0.781010 68236.467078 189689.298378 0.000000 527410.776663 0.000000 788.147120
+EDGE_SE2 835 836 0.015546 0.007972 0.947065 68058.939717 132897.198385 0.000000 259558.927707 0.000000 659.445803
+EDGE_SE2 836 837 0.017648 0.011594 1.040763 44125.577264 89148.384604 0.000000 180165.948528 0.000000 600.281370
+EDGE_SE2 837 838 0.013822 0.005479 0.865867 99632.035075 187458.017071 0.000000 352753.354065 0.000000 718.089607
+EDGE_SE2 838 839 0.001331 -0.000521 -0.216716 1187297.905481 7527754.381697 0.000000 47728231.706064 0.000000 1688.735256
+EDGE_SE2 839 840 0.014201 -0.005576 -0.560094 14691.670684 -78049.547320 0.000000 414963.402725 0.000000 1027.160891
+EDGE_SE2 840 841 0.018508 -0.004844 -0.614349 33618.056740 -89734.585298 0.000000 239613.242398 0.000000 959.279471
+EDGE_SE2 841 842 0.244308 -0.051175 -0.229250 11.937138 -36.275589 0.000000 1604.181092 0.000000 1654.472583
+EDGE_SE2 842 843 0.571578 -0.004308 -0.001490 11.121898 1.783710 0.000000 306.061619 0.000000 2492.566618
+EDGE_SE2 843 844 0.632633 0.008356 -0.006975 11.208334 -4.816449 0.000000 249.718690 0.000000 2465.486516
+EDGE_SE2 844 845 0.634632 -0.005065 -0.013668 11.118782 -1.348758 0.000000 248.265069 0.000000 2433.036002
+EDGE_SE2 845 846 0.637586 0.012768 0.002757 11.181094 -4.052879 0.000000 245.824022 0.000000 2486.271799
+EDGE_SE2 846 847 0.633522 -0.013243 -0.025675 11.116535 -1.135991 0.000000 249.044882 0.000000 2376.405061
+EDGE_SE2 847 848 0.158686 0.003991 0.484189 788.091041 1572.022678 0.000000 3191.702019 0.000000 1134.910441
+EDGE_SE2 848 849 0.002564 0.003351 0.928473 680.469413 61313.177701 0.000000 5616294.276467 0.000000 672.222250
+EDGE_SE2 849 850 0.350597 0.124336 0.356364 11.283371 11.069863 0.000000 722.488046 0.000000 1358.900004
+EDGE_SE2 850 851 0.642798 -0.027661 -0.090713 11.635228 -10.977882 0.000000 241.048137 0.000000 2101.449848
+EDGE_SE2 851 852 0.640836 -0.004293 0.015855 11.229301 5.239393 0.000000 243.375111 0.000000 2422.571276
+EDGE_SE2 852 853 0.610781 0.003140 -0.026553 11.369134 -8.138170 0.000000 267.793422 0.000000 2372.341770
+EDGE_SE2 853 854 0.603861 -0.006364 0.003213 11.160858 3.617435 0.000000 274.156807 0.000000 2484.012095
+EDGE_SE2 854 855 0.610860 0.010420 -0.000693 11.192009 -4.557204 0.000000 267.830171 0.000000 2496.538599
+EDGE_SE2 855 856 0.637641 -0.018640 -0.037084 11.125605 -1.844014 0.000000 245.725607 0.000000 2324.406817
+EDGE_SE2 856 857 0.637311 0.003614 -0.006131 11.143851 -2.774089 0.000000 246.164229 0.000000 2469.624632
+EDGE_SE2 857 858 0.636231 -0.022329 -0.050745 11.168921 -3.690286 0.000000 246.680327 0.000000 2264.359323
+EDGE_SE2 858 859 0.507785 0.004334 -0.003406 11.164814 -4.497374 0.000000 387.747642 0.000000 2483.056613
+EDGE_SE2 859 860 0.002497 0.001745 0.863794 679539.881456 2619251.092498 0.000000 10095943.152469 0.000000 719.687882
+EDGE_SE2 860 861 0.070325 0.071481 0.928711 191.497025 1326.435969 0.000000 9764.823807 0.000000 672.056358
+EDGE_SE2 861 862 0.652508 -0.024736 -0.055891 11.183497 -4.020862 0.000000 234.461196 0.000000 2242.341901
+EDGE_SE2 862 863 0.638309 -0.005836 -0.029014 11.203612 -4.654534 0.000000 245.322644 0.000000 2361.007908
+EDGE_SE2 863 864 0.606532 -0.017964 0.001104 11.356731 7.994878 0.000000 271.342913 0.000000 2494.489128
+EDGE_SE2 864 865 0.604147 0.028266 0.061183 11.165720 3.784052 0.000000 273.324162 0.000000 2220.033054
+EDGE_SE2 865 866 0.579332 -0.011435 0.001982 11.246334 6.225212 0.000000 297.699601 0.000000 2490.119385
+EDGE_SE2 866 867 0.156548 0.001719 0.185575 133.883281 696.034953 0.000000 3957.157327 0.000000 1778.614047
+EDGE_SE2 867 868 0.017881 0.010690 1.037717 52749.955417 96798.086518 0.000000 177676.543047 0.000000 602.077325
+EDGE_SE2 868 869 0.012235 0.005926 0.991656 143324.570378 238746.643887 0.000000 397740.398080 0.000000 630.247818
+EDGE_SE2 869 870 0.002231 -0.000124 1.013097 15395648.131442 8450866.436031 0.000000 4638802.180641 0.000000 616.894084
+EDGE_SE2 870 871 0.001088 0.001679 0.986895 2024.695825 -224276.785530 0.000000 24980373.832027 0.000000 633.271838
+EDGE_SE2 871 872 0.008015 -0.000084 0.694560 653702.249121 768245.705891 0.000000 902886.231030 0.000000 870.614924
+EDGE_SE2 872 873 0.008522 -0.003526 -0.564717 34612.893765 -198701.425503 0.000000 1141058.001437 0.000000 1021.100307
+EDGE_SE2 873 874 0.015858 -0.003778 -0.551904 36802.135033 -111762.498404 0.000000 339519.358447 0.000000 1038.030952
+EDGE_SE2 874 875 0.013521 -0.001487 -0.578534 110429.389804 -217905.190004 0.000000 430036.577843 0.000000 1003.303038
+EDGE_SE2 875 876 0.574406 -0.080596 -0.153354 11.166806 -3.991544 0.000000 297.175644 0.000000 1879.380673
+EDGE_SE2 876 877 0.574770 -0.024813 -0.080909 11.525988 -10.980326 0.000000 301.721640 0.000000 2139.743633
+EDGE_SE2 877 878 0.217632 0.014817 0.389316 219.643265 626.455159 0.000000 1893.056212 0.000000 1295.203276
+EDGE_SE2 878 879 0.647020 0.057742 0.054681 11.377140 -7.747124 0.000000 236.717936 0.000000 2247.489979
+EDGE_SE2 879 880 0.455025 -0.018050 -0.108582 13.346224 -32.372663 0.000000 479.986413 0.000000 2034.250181
+EDGE_SE2 880 881 -0.043409 -0.000133 0.008718 12.813581 300.540520 0.000000 53066.151297 0.000000 2456.973472
+EDGE_SE2 881 882 0.647486 -0.064933 -0.241227 15.572920 -31.371721 0.000000 231.690918 0.000000 1622.697550
+EDGE_SE2 882 883 0.642883 -0.072854 -0.185824 12.322147 -16.564386 0.000000 237.676574 0.000000 1777.868098
+EDGE_SE2 883 884 0.383517 -0.007350 -0.063028 12.396618 -29.287057 0.000000 678.343333 0.000000 2212.333526
+EDGE_SE2 884 885 0.004929 0.003007 0.590777 5527.682570 128525.333864 0.000000 2994400.210829 0.000000 987.919146
+EDGE_SE2 885 886 0.007741 0.006994 1.034072 79878.863906 258839.772996 0.000000 838873.176713 0.000000 604.237070
+EDGE_SE2 886 887 0.010004 0.001000 1.027322 633501.134354 474724.505488 0.000000 355759.975090 0.000000 608.267401
+EDGE_SE2 887 888 0.005011 0.003332 0.999568 444415.889744 1014710.716533 0.000000 2316903.025310 0.000000 625.269895
+EDGE_SE2 888 889 0.005294 0.002083 0.911927 808634.909964 1357982.238784 0.000000 2280571.939853 0.000000 683.907547
+EDGE_SE2 889 890 0.355203 0.095914 0.279682 11.296105 11.600417 0.000000 738.538555 0.000000 1526.637360
+EDGE_SE2 890 891 0.616728 -0.012401 -0.066427 11.650788 -11.642307 0.000000 262.267312 0.000000 2198.253354
+EDGE_SE2 891 892 0.637263 -0.017865 -0.031981 11.114783 -0.928852 0.000000 246.045454 0.000000 2347.451378
+EDGE_SE2 892 893 0.642710 0.035710 0.241471 18.981950 41.834853 0.000000 233.470505 0.000000 1622.059760
+EDGE_SE2 893 894 0.638528 0.083732 0.226070 13.210427 21.873674 0.000000 239.022296 0.000000 1663.065968
+EDGE_SE2 894 895 0.615722 0.105457 0.303953 15.507767 32.534377 0.000000 251.859007 0.000000 1470.334450
+EDGE_SE2 895 896 0.020155 0.000491 0.481484 47934.902135 97432.832108 0.000000 198099.713240 0.000000 1139.058627
+EDGE_SE2 896 897 0.528670 0.158235 0.274351 11.197167 -5.224460 0.000000 328.288174 0.000000 1539.436858
+EDGE_SE2 897 898 0.618615 0.002949 0.017900 11.154262 3.285463 0.000000 261.262932 0.000000 2412.846978
+EDGE_SE2 898 899 0.499807 -0.008373 -0.065092 12.019606 -18.779145 0.000000 399.287489 0.000000 2203.767446
+EDGE_SE2 899 900 0.683722 0.007464 -0.000025 11.135386 -2.218523 0.000000 213.865098 0.000000 2499.875005
+EDGE_SE2 900 901 0.579956 -0.019520 -0.061673 11.335628 -8.008145 0.000000 296.748861 0.000000 2217.984277
+EDGE_SE2 901 902 0.644996 0.015819 0.027799 11.113573 0.751022 0.000000 240.226171 0.000000 2366.593280
+EDGE_SE2 902 903 0.494510 0.003386 -0.042100 12.063405 -19.440085 0.000000 407.959954 0.000000 2302.084267
+EDGE_SE2 903 904 0.005815 0.000708 0.715026 912712.732392 1351574.977076 0.000000 2001492.072759 0.000000 849.960204
+EDGE_SE2 904 905 0.554057 0.035513 0.058326 11.121228 -1.780350 0.000000 324.412517 0.000000 2232.035396
+EDGE_SE2 905 906 0.630376 0.024475 0.068969 11.329543 7.239573 0.000000 251.055279 0.000000 2187.810926
+EDGE_SE2 906 907 0.631021 0.007133 -0.005018 11.175042 -3.916492 0.000000 251.041590 0.000000 2475.097597
+EDGE_SE2 907 908 0.637636 0.001891 0.024788 11.222935 5.123325 0.000000 245.840507 0.000000 2380.520611
+EDGE_SE2 908 909 0.628314 0.001550 -0.017825 11.210816 -4.913046 0.000000 253.205497 0.000000 2413.202580
+EDGE_SE2 909 910 0.147710 -0.043678 -0.369688 39.436166 -343.900479 0.000000 4186.479576 0.000000 1332.590482
+EDGE_SE2 910 911 0.616085 0.011620 0.061065 11.560202 10.634138 0.000000 262.919471 0.000000 2220.526856
+EDGE_SE2 911 912 0.605554 0.006436 0.010902 11.111131 0.071773 0.000000 272.675019 0.000000 2446.368619
+EDGE_SE2 912 913 0.580860 0.003431 0.006628 11.111259 0.205638 0.000000 296.374652 0.000000 2467.186590
+EDGE_SE2 913 914 0.630196 -0.006309 -0.024572 11.162137 -3.503890 0.000000 251.720029 0.000000 2381.524439
+EDGE_SE2 914 915 0.556525 -0.006690 -0.037260 11.309630 -7.863953 0.000000 322.627351 0.000000 2323.618084
+EDGE_SE2 915 916 0.178865 0.104304 0.546671 11.926058 43.487541 0.000000 2331.711773 0.000000 1045.066974
+EDGE_SE2 916 917 0.624756 -0.045966 -0.254265 18.993145 -43.113795 0.000000 246.938496 0.000000 1589.137227
+EDGE_SE2 917 918 0.518933 -0.035276 -0.074995 11.129291 -2.552939 0.000000 369.618783 0.000000 2163.351655
+EDGE_SE2 918 919 0.629099 -0.005797 -0.042335 11.375987 -7.994276 0.000000 252.388154 0.000000 2301.046350
+EDGE_SE2 919 920 0.629899 -0.010656 -0.016202 11.111234 0.171926 0.000000 251.961442 0.000000 2420.917100
+EDGE_SE2 920 921 0.634457 -0.008549 -0.051374 11.451756 -8.983787 0.000000 248.039729 0.000000 2261.650760
+EDGE_SE2 921 922 0.635258 -0.006313 -0.024873 11.163905 -3.534345 0.000000 247.721599 0.000000 2380.125761
+EDGE_SE2 922 923 0.608430 -0.014168 -0.060475 11.469047 -9.619410 0.000000 269.629762 0.000000 2222.998344
+EDGE_SE2 923 924 0.530888 -0.000682 0.019383 11.257903 7.101435 0.000000 354.661710 0.000000 2405.831657
+EDGE_SE2 924 925 0.009664 0.004698 0.510887 2959.553169 50448.307002 0.000000 863189.572650 0.000000 1095.156133
+EDGE_SE2 925 926 0.598427 0.009230 0.018979 11.114501 0.953220 0.000000 279.170216 0.000000 2407.739741
+EDGE_SE2 926 927 0.627907 -0.001812 -0.020475 11.186132 -4.264817 0.000000 253.558182 0.000000 2400.685500
+EDGE_SE2 927 928 0.640773 -0.000139 -0.006135 11.119254 -1.375744 0.000000 243.544155 0.000000 2469.604995
+EDGE_SE2 928 929 0.636560 -0.000176 0.001919 11.112246 0.517244 0.000000 246.784978 0.000000 2490.432549
+EDGE_SE2 929 930 0.640386 -0.014253 -0.078843 11.855260 -13.135681 0.000000 242.981611 0.000000 2147.946760
+EDGE_SE2 930 931 0.635431 -0.020570 -0.076099 11.562880 -10.322123 0.000000 246.953500 0.000000 2158.915046
+EDGE_SE2 931 932 0.639769 -0.010067 -0.055067 11.471607 -9.160668 0.000000 243.895776 0.000000 2245.845776
+EDGE_SE2 932 933 0.631644 -0.015304 -0.059766 11.413371 -8.500896 0.000000 250.193846 0.000000 2225.973780
+EDGE_SE2 933 934 0.504140 0.003029 -0.005219 11.159305 -4.292306 0.000000 393.395672 0.000000 2474.107872
+EDGE_SE2 934 935 0.005622 0.001555 0.696880 504282.663987 1107982.483573 0.000000 2434463.693063 0.000000 868.235915
+EDGE_SE2 935 936 0.001863 0.001286 0.945362 2184651.299423 6152115.682451 0.000000 17324844.542602 0.000000 660.600886
+EDGE_SE2 936 937 0.551720 0.024485 0.062876 11.219817 5.867053 0.000000 327.765518 0.000000 2212.966335
+EDGE_SE2 937 938 0.601673 -0.055314 -0.173492 12.866388 -21.406117 0.000000 272.165004 0.000000 1815.430979
+EDGE_SE2 938 939 0.633059 0.008315 0.027580 11.160855 3.443094 0.000000 249.431085 0.000000 2367.602135
+EDGE_SE2 939 940 0.636273 -0.027491 -0.082722 11.479060 -9.300191 0.000000 246.180789 0.000000 2132.583702
+EDGE_SE2 940 941 0.635944 -0.015109 -0.050698 11.282417 -6.356188 0.000000 246.953620 0.000000 2264.561906
+EDGE_SE2 941 942 0.551791 -0.000493 0.007207 11.131937 2.570602 0.000000 328.415327 0.000000 2464.350846
+EDGE_SE2 942 943 0.644097 -0.001397 0.091523 13.123577 21.416835 0.000000 239.030853 0.000000 2098.332107
+EDGE_SE2 943 944 0.639009 -0.005732 -0.053678 11.578073 -10.437551 0.000000 244.411524 0.000000 2251.770804
+EDGE_SE2 944 945 0.635846 -0.012134 -0.052894 11.381001 -7.978646 0.000000 246.980906 0.000000 2255.125454
+EDGE_SE2 945 946 0.179699 -0.002044 0.066572 29.818272 239.512661 0.000000 3077.654110 0.000000 2197.655692
+EDGE_SE2 946 947 0.406915 0.138311 0.331627 11.119495 2.108463 0.000000 541.380410 0.000000 1409.856218
+EDGE_SE2 947 948 0.579846 -0.001426 -0.021963 11.220001 -5.582502 0.000000 297.312605 0.000000 2393.699690
+EDGE_SE2 948 949 0.604761 -0.049058 -0.159219 12.704160 -20.309811 0.000000 270.041237 0.000000 1860.411550
+EDGE_SE2 949 950 0.636468 -0.025408 -0.243519 20.734999 -46.608998 0.000000 236.840951 0.000000 1616.721292
+EDGE_SE2 950 951 0.637412 -0.014316 -0.075046 11.760145 -12.330103 0.000000 245.353687 0.000000 2163.146402
+EDGE_SE2 951 952 0.637647 0.028692 0.246962 20.543292 46.058094 0.000000 236.016458 0.000000 1607.805725
+EDGE_SE2 952 953 0.635715 0.017895 0.077527 11.686555 11.642681 0.000000 246.671765 0.000000 2153.196604
+EDGE_SE2 953 954 0.632201 -0.012369 -0.013007 11.121379 1.566520 0.000000 250.095671 0.000000 2436.212212
+EDGE_SE2 954 955 0.636040 -0.066402 -0.167279 12.043873 -14.725801 0.000000 243.592003 0.000000 1834.808164
+EDGE_SE2 955 956 0.633169 -0.005303 -0.005934 11.112531 0.581642 0.000000 249.417984 0.000000 2470.592019
+EDGE_SE2 956 957 0.635780 -0.029022 -0.090789 11.591896 -10.635874 0.000000 246.396892 0.000000 2101.157024
+EDGE_SE2 957 958 0.610078 -0.010922 -0.028564 11.140389 -2.745454 0.000000 268.560860 0.000000 2363.074257
+EDGE_SE2 958 959 0.604449 -0.016600 -0.068060 11.543478 -10.642379 0.000000 273.065197 0.000000 2191.536497
+EDGE_SE2 959 960 0.605875 0.054020 0.088370 11.111191 -0.143784 0.000000 270.268197 0.000000 2110.507423
+EDGE_SE2 960 961 0.602054 -0.007561 -0.020089 11.126126 -1.993676 0.000000 275.827437 0.000000 2402.502675
+EDGE_SE2 961 962 0.630743 0.063738 0.073005 11.293528 -6.582439 0.000000 248.635890 0.000000 2171.383420
+EDGE_SE2 962 963 0.629692 0.069822 0.195655 12.835701 20.187165 0.000000 247.411650 0.000000 1748.752064
+EDGE_SE2 963 964 0.639791 -0.008273 -0.057447 11.572861 -10.365475 0.000000 243.797913 0.000000 2235.747685
+EDGE_SE2 964 965 0.633282 -0.006211 -0.001478 11.127639 1.984141 0.000000 249.307749 0.000000 2492.626351
+EDGE_SE2 965 966 0.413197 -0.005006 -0.057147 12.275386 -25.836778 0.000000 584.463061 0.000000 2237.016798
+EDGE_SE2 966 967 0.007510 0.002997 0.859092 325478.163261 626027.365559 0.000000 1204158.381440 0.000000 723.332943
+EDGE_SE2 967 968 0.006374 0.000527 0.902649 1307259.212480 1219284.216016 0.000000 1137250.475138 0.000000 690.593544
+EDGE_SE2 968 969 0.000997 0.000085 0.061289 54733.539945 -2337658.966155 0.000000 99861248.240381 0.000000 2219.589608
+EDGE_SE2 969 970 0.000000 0.000000 -0.000113 11.111116 -0.043944 0.000000 399.999995 0.000000 2499.435096
+EDGE_SE2 970 971 0.361971 0.001286 0.001712 11.113656 -1.383525 0.000000 763.211229 0.000000 2491.461932
+EDGE_SE2 971 972 0.616031 0.005441 0.007131 11.111841 -0.429263 0.000000 263.487396 0.000000 2464.722790
+EDGE_SE2 972 973 0.597393 -0.119850 -0.282715 12.960368 -21.775201 0.000000 267.516438 0.000000 1519.426379
+EDGE_SE2 973 974 0.636084 -0.002771 0.033166 11.443293 8.848623 0.000000 246.819403 0.000000 2342.069601
+EDGE_SE2 974 975 0.636019 0.005980 0.005775 11.114215 -0.856039 0.000000 247.181135 0.000000 2471.373217
+EDGE_SE2 975 976 0.637784 0.010421 0.013983 11.112413 -0.552665 0.000000 245.773095 0.000000 2431.524562
+EDGE_SE2 976 977 0.637920 -0.011711 -0.026304 11.125929 -1.864213 0.000000 245.637352 0.000000 2373.493056
+EDGE_SE2 977 978 0.636711 0.018679 0.044825 11.167625 3.646515 0.000000 246.400847 0.000000 2290.091830
+EDGE_SE2 978 979 0.635616 -0.004880 -0.014420 11.121860 -1.593981 0.000000 247.494628 0.000000 2429.430070
+EDGE_SE2 979 980 0.640402 0.020748 0.043464 11.139636 2.574932 0.000000 243.549790 0.000000 2296.069703
+EDGE_SE2 980 981 0.634599 -0.001102 0.002602 11.115574 1.028911 0.000000 248.309152 0.000000 2487.040602
+EDGE_SE2 981 982 0.582350 0.019314 0.039136 11.121253 1.695467 0.000000 294.536681 0.000000 2315.235788
+EDGE_SE2 982 983 0.606004 -0.005123 -0.005706 11.113084 0.717739 0.000000 272.279670 0.000000 2471.712344
+EDGE_SE2 983 984 0.606209 0.019467 0.054452 11.241333 5.825396 0.000000 271.705807 0.000000 2248.466280
+EDGE_SE2 984 985 0.610191 0.001384 0.017236 11.168792 3.853233 0.000000 268.517439 0.000000 2415.997974
+EDGE_SE2 985 986 0.638807 0.015817 0.032823 11.126330 1.886242 0.000000 244.888150 0.000000 2343.625460
+EDGE_SE2 986 987 0.637113 -0.009662 -0.040633 11.263641 -5.987507 0.000000 246.149046 0.000000 2308.579426
+EDGE_SE2 987 988 0.633843 -0.002158 0.009656 11.151672 3.105391 0.000000 248.863041 0.000000 2452.410392
+EDGE_SE2 988 989 0.637783 0.006714 0.004244 11.120373 -1.474376 0.000000 245.804243 0.000000 2478.914326
+EDGE_SE2 989 990 0.633086 -0.006222 -0.014570 11.116473 -1.130568 0.000000 249.472636 0.000000 2428.711760
+EDGE_SE2 990 991 0.638433 0.009419 0.020655 11.119271 1.382293 0.000000 245.278829 0.000000 2399.838818
+EDGE_SE2 991 992 0.608534 -0.016202 -0.037230 11.140243 -2.745311 0.000000 269.821049 0.000000 2323.752499
+EDGE_SE2 992 993 0.639975 0.012788 0.027838 11.125497 1.830546 0.000000 244.047684 0.000000 2366.413689
+EDGE_SE2 993 994 0.610172 -0.004541 -0.015063 11.126066 -1.962186 0.000000 268.563253 0.000000 2426.353160
+EDGE_SE2 994 995 0.582700 0.014385 0.047816 11.262674 6.550087 0.000000 294.185844 0.000000 2277.036316
+EDGE_SE2 995 996 0.603243 0.013060 0.027432 11.119936 1.525036 0.000000 274.662056 0.000000 2368.284283
+EDGE_SE2 996 997 0.638105 -0.021586 -0.064337 11.329213 -7.143676 0.000000 245.093679 0.000000 2206.895091
+EDGE_SE2 997 998 0.393437 0.003178 0.021791 11.230485 8.704766 0.000000 645.865055 0.000000 2394.505630
+EDGE_SE2 998 999 0.009526 0.010297 0.717647 5765.419520 -53770.217970 0.000000 502458.344534 0.000000 847.368232
+EDGE_SE2 999 1000 0.631982 0.082779 0.148351 11.188179 4.255373 0.000000 246.074510 0.000000 1895.792072
+EDGE_SE2 1000 1001 0.637485 -0.061202 -0.321633 22.788129 -50.803890 0.000000 232.146590 0.000000 1431.259099
+EDGE_SE2 1001 1002 0.630663 0.034533 0.091989 11.444015 8.924103 0.000000 250.338290 0.000000 2096.541587
+EDGE_SE2 1002 1003 0.637376 -0.055899 -0.180665 13.130018 -21.602372 0.000000 242.257264 0.000000 1793.439086
+EDGE_SE2 1003 1004 0.634119 0.020824 0.062770 11.323812 7.101476 0.000000 248.209237 0.000000 2213.407797
+EDGE_SE2 1004 1005 0.602568 0.019724 0.067274 11.426188 9.115028 0.000000 274.805024 0.000000 2194.765624
+EDGE_SE2 1005 1006 0.609599 0.024909 0.082661 11.561301 10.758208 0.000000 268.200258 0.000000 2132.824020
+EDGE_SE2 1006 1007 0.575806 0.024121 0.097394 12.004289 16.068550 0.000000 300.189527 0.000000 2075.940233
+EDGE_SE2 1007 1008 0.296743 0.004461 0.166242 36.620925 167.418708 0.000000 1109.865632 0.000000 1838.072567
+EDGE_SE2 1008 1009 0.169516 0.079531 0.456955 12.060231 51.919506 0.000000 2851.251647 0.000000 1177.735408
+EDGE_SE2 1009 1010 0.635352 0.000090 0.046389 11.616830 10.927244 0.000000 247.219830 0.000000 2283.251111
+EDGE_SE2 1010 1011 0.629760 -0.000818 -0.047667 11.628961 -11.160233 0.000000 251.626406 0.000000 2277.684046
+EDGE_SE2 1011 1012 0.630488 0.001328 0.037830 11.417845 8.582558 0.000000 251.254815 0.000000 2321.066416
+EDGE_SE2 1012 1013 0.638821 0.043192 0.110754 11.546239 10.055629 0.000000 243.492562 0.000000 2026.302298
+EDGE_SE2 1013 1014 0.624005 -0.081360 -0.179557 11.711863 -12.027816 0.000000 251.923335 0.000000 1796.809951
+EDGE_SE2 1014 1015 0.637514 0.038828 0.081332 11.209468 4.796725 0.000000 245.041047 0.000000 2138.069893
+EDGE_SE2 1015 1016 0.781423 -0.009024 0.004462 11.150231 2.443265 0.000000 163.706442 0.000000 2477.838437
+EDGE_SE2 1016 1017 0.603503 0.011706 -0.057436 12.662554 -20.153468 0.000000 272.907609 0.000000 2235.794200
+EDGE_SE2 1017 1018 0.577934 -0.006330 0.007000 11.203996 5.173502 0.000000 299.265589 0.000000 2465.364100
+EDGE_SE2 1018 1019 0.612439 0.031252 0.059177 11.128209 2.087199 0.000000 265.898770 0.000000 2228.450161
+EDGE_SE2 1019 1020 0.633556 -0.016343 -0.014332 11.142340 2.725270 0.000000 248.935660 0.000000 2429.851626
+EDGE_SE2 1020 1021 0.639472 -0.000168 -0.041050 11.499240 -9.510600 0.000000 244.155855 0.000000 2306.730360
+EDGE_SE2 1021 1022 0.070832 0.000271 -0.007651 13.732233 -228.486723 0.000000 19928.608606 0.000000 2462.179597
+EDGE_SE2 1022 1023 0.011155 0.000820 0.086100 139.654009 10135.503712 0.000000 799187.396127 0.000000 2119.338762
+EDGE_SE2 1023 1024 0.645203 -0.002963 0.025849 11.323339 6.969723 0.000000 240.001559 0.000000 2375.598978
+EDGE_SE2 1024 1025 0.648616 0.019366 0.017058 11.148143 -2.895107 0.000000 237.448652 0.000000 2416.843718
+EDGE_SE2 1025 1026 0.180366 -0.000503 0.006661 11.384697 28.945754 0.000000 3073.606781 0.000000 2467.024836
+EDGE_SE2 1026 1027 0.004554 0.001979 0.914665 948112.591095 1716536.548028 0.000000 3107798.392242 0.000000 681.952949
+EDGE_SE2 1027 1028 0.157112 0.092209 0.562259 14.094418 94.590688 0.000000 3010.265300 0.000000 1024.315957
+EDGE_SE2 1028 1029 0.581697 -0.003158 -0.022026 11.189449 -4.719569 0.000000 295.446261 0.000000 2393.404593
+EDGE_SE2 1029 1030 0.602428 -0.021526 -0.077659 11.575380 -11.062953 0.000000 274.727843 0.000000 2152.669156
+EDGE_SE2 1030 1031 0.635032 -0.016817 -0.051435 11.258521 -5.904986 0.000000 247.654252 0.000000 2261.388344
+EDGE_SE2 1031 1032 0.639363 0.000529 0.006615 11.118933 1.351453 0.000000 244.619567 0.000000 2467.250316
+EDGE_SE2 1032 1033 0.641217 -0.014716 -0.042294 11.197935 -4.487022 0.000000 242.999818 0.000000 2301.227383
+EDGE_SE2 1033 1034 0.158807 -0.001999 -0.209870 162.997809 -759.872169 0.000000 3812.666625 0.000000 1707.900606
+EDGE_SE2 1034 1035 0.008238 -0.003621 -0.612225 47839.602807 -238285.590348 0.000000 1187170.073357 0.000000 961.808711
+EDGE_SE2 1035 1036 -0.001359 0.001797 -0.564077 2434530.032209 6484761.501388 0.000000 17273293.058299 0.000000 1021.936120
+EDGE_SE2 1036 1037 0.377894 -0.111886 -0.234247 12.927670 33.853486 0.000000 642.006396 0.000000 1641.103033
+EDGE_SE2 1037 1038 0.646416 0.075596 0.094513 11.219032 -4.926286 0.000000 235.981250 0.000000 2086.883283
+EDGE_SE2 1038 1039 0.688482 -0.025514 -0.028564 11.125452 1.691699 0.000000 210.663547 0.000000 2363.074257
+EDGE_SE2 1039 1040 -0.001379 -0.000331 0.637825 7632266.679736 17921038.113983 0.000000 42079787.422993 0.000000 931.976618
+EDGE_SE2 1040 1041 -0.001323 0.000722 1.029242 43947061.658526 1853405.592364 0.000000 78175.908225 0.000000 607.116902
+EDGE_SE2 1041 1042 0.008412 0.001092 0.999819 812869.525001 684736.258072 0.000000 576819.734984 0.000000 625.113140
+EDGE_SE2 1042 1043 0.010022 0.000228 0.981327 666387.833541 467987.047537 0.000000 328671.866042 0.000000 636.836128
+EDGE_SE2 1043 1044 -0.013611 -0.010605 1.005709 38168.445431 106580.996550 0.000000 297712.956067 0.000000 621.446905
+EDGE_SE2 1044 1045 -0.002205 0.000124 -0.113838 68490.084727 -1183057.512679 0.000000 20438767.774721 0.000000 2015.095849
+EDGE_SE2 1045 1046 -0.013495 0.002112 -0.385242 27867.951272 -118972.940165 0.000000 508129.060237 0.000000 1302.832870
+EDGE_SE2 1046 1047 -0.019733 0.005898 -0.555401 16179.611132 -59582.091055 0.000000 219575.422578 0.000000 1033.368600
+EDGE_SE2 1047 1048 0.344577 -0.119470 -0.312747 11.437653 15.549100 0.000000 751.519224 0.000000 1450.701098
+EDGE_SE2 1048 1049 0.648714 0.010953 0.017287 11.111148 0.091735 0.000000 237.558159 0.000000 2415.755736
+EDGE_SE2 1049 1050 0.646643 0.027376 0.075802 11.366332 7.617483 0.000000 238.466970 0.000000 2160.107247
+EDGE_SE2 1050 1051 0.640459 -0.024485 -0.073431 11.399152 -8.175325 0.000000 243.147148 0.000000 2169.660298
+EDGE_SE2 1051 1052 0.610691 0.014345 0.058571 11.427186 9.005158 0.000000 267.673485 0.000000 2231.002333
+EDGE_SE2 1052 1053 0.402418 -0.011887 -0.047093 11.297991 -10.639018 0.000000 616.787282 0.000000 2280.181912
+EDGE_SE2 1053 1054 0.003611 0.000205 0.781659 3360883.673888 3794299.768961 0.000000 4283634.029810 0.000000 787.573032
+EDGE_SE2 1054 1055 -0.004781 -0.004680 1.092196 217607.587361 662404.612456 0.000000 2016495.376692 0.000000 571.130228
+EDGE_SE2 1055 1056 -0.018363 -0.010043 1.033833 59014.075212 99936.588877 0.000000 169279.247866 0.000000 604.379088
+EDGE_SE2 1056 1057 -0.018154 -0.006925 1.003259 94181.986455 126785.732418 0.000000 170707.431880 0.000000 622.968093
+EDGE_SE2 1057 1058 0.000938 0.000345 0.933655 30225249.079874 45961533.817447 0.000000 69890696.274135 0.000000 668.624102
+EDGE_SE2 1058 1059 0.584768 -0.021106 -0.077373 11.589927 -11.588453 0.000000 291.578229 0.000000 2153.812205
+EDGE_SE2 1059 1060 0.639269 -0.001644 0.007968 11.137057 2.461692 0.000000 244.671355 0.000000 2460.631159
+EDGE_SE2 1060 1061 0.453408 -0.013544 -0.118843 14.861134 -42.033048 0.000000 482.248782 0.000000 1997.108732
+EDGE_SE2 1061 1062 0.018407 -0.004707 -0.560522 25818.783584 -80519.505627 0.000000 251230.619305 0.000000 1026.597536
+EDGE_SE2 1062 1063 -0.002214 0.000350 -0.593849 3568021.016682 -7633088.462779 0.000000 16329573.254319 0.000000 984.114566
+EDGE_SE2 1063 1064 0.301240 -0.082154 -0.262828 11.122946 3.465125 0.000000 1025.683739 0.000000 1567.659011
+EDGE_SE2 1064 1065 0.616850 0.043972 0.123884 11.806351 13.175109 0.000000 260.785525 0.000000 1979.233494
+EDGE_SE2 1065 1066 0.592225 -0.017770 -0.054423 11.274422 -6.684300 0.000000 284.699249 0.000000 2248.589962
+EDGE_SE2 1066 1067 0.012072 0.002120 0.435817 44661.394679 166520.359722 0.000000 621038.078606 0.000000 1212.667746
+EDGE_SE2 1067 1068 0.005144 0.001599 0.677089 463864.684926 1176104.562755 0.000000 2982033.931716 0.000000 888.848590
+EDGE_SE2 1068 1069 0.004939 0.001172 0.172450 14196.268745 -234184.920951 0.000000 3866205.524763 0.000000 1818.659296
+EDGE_SE2 1069 1070 0.007958 -0.000773 -0.535379 282034.324000 -601390.067166 0.000000 1282423.325271 0.000000 1060.495466
+EDGE_SE2 1070 1071 0.555140 -0.067868 -0.125252 11.115112 -1.111199 0.000000 319.703282 0.000000 1974.424001
+EDGE_SE2 1071 1072 0.529254 -0.007703 -0.066861 12.056408 -18.055610 0.000000 355.981837 0.000000 2196.465215
+EDGE_SE2 1072 1073 -0.002029 0.000845 -0.507518 262958.959876 -2318685.557147 0.000000 20446281.115523 0.000000 1100.056511
+EDGE_SE2 1073 1074 0.561059 -0.025535 -0.032676 11.161259 3.916370 0.000000 316.967702 0.000000 2344.292731
+EDGE_SE2 1074 1075 0.609431 -0.004618 0.018200 11.282578 6.650541 0.000000 269.060256 0.000000 2411.425356
+EDGE_SE2 1075 1076 0.065495 0.001481 0.413124 3385.912605 8198.067984 0.000000 19925.858335 0.000000 1251.928321
+EDGE_SE2 1076 1077 0.014156 0.014258 0.821400 271.376246 8025.080869 0.000000 247458.480551 0.000000 753.579966
+EDGE_SE2 1077 1078 0.639455 0.059020 0.049931 11.521069 -9.730785 0.000000 242.081388 0.000000 2267.871749
+EDGE_SE2 1078 1079 0.600624 0.018085 0.067237 11.477555 9.863097 0.000000 276.583452 0.000000 2194.917807
+EDGE_SE2 1079 1080 -0.000999 -0.000009 -0.477168 21861087.771847 -41382475.748765 0.000000 78336011.010556 0.000000 1145.724571
+EDGE_SE2 1080 1081 0.531360 -0.067180 -0.117428 11.134556 2.812802 0.000000 348.582744 0.000000 2002.169815
+EDGE_SE2 1081 1082 0.224996 0.001967 0.288640 161.010437 521.488265 0.000000 1825.328808 0.000000 1505.486248
+EDGE_SE2 1082 1083 -0.010460 -0.011699 1.057628 18726.686416 85143.154920 0.000000 387354.631781 0.000000 590.481488
+EDGE_SE2 1083 1084 0.006499 0.006279 0.991072 59854.087388 264007.010053 0.000000 1164720.918244 0.000000 630.617587
+EDGE_SE2 1084 1085 0.020056 0.011249 0.977075 38176.449616 75898.227624 0.000000 150947.567649 0.000000 639.578299
+EDGE_SE2 1085 1086 0.570700 0.124357 0.228493 11.165939 3.931749 0.000000 293.059740 0.000000 1656.511362
+EDGE_SE2 1086 1087 0.610443 -0.014761 -0.013224 11.141951 2.815599 0.000000 268.167634 0.000000 2435.168807
+EDGE_SE2 1087 1088 0.601056 0.009570 -0.017713 11.411487 -8.927269 0.000000 276.432474 0.000000 2413.733758
+EDGE_SE2 1088 1089 0.071683 -0.000572 -0.098521 170.122570 -1751.356223 0.000000 19300.592801 0.000000 2071.681742
+EDGE_SE2 1089 1090 0.001412 -0.000123 -0.621871 12937756.646628 -21836745.706848 0.000000 36856777.365825 0.000000 950.402110
+EDGE_SE2 1090 1091 0.549397 -0.084430 -0.180259 11.352156 -8.676436 0.000000 323.419744 0.000000 1794.673157
+EDGE_SE2 1091 1092 0.637703 -0.006996 -0.017526 11.121203 -1.539154 0.000000 245.862562 0.000000 2414.621027
+EDGE_SE2 1092 1093 0.588555 -0.015042 -0.067587 11.600931 -11.646012 0.000000 288.008196 0.000000 2193.478870
+EDGE_SE2 1093 1094 0.004150 -0.003600 -0.406987 303638.185583 955915.435697 0.000000 3009539.565685 0.000000 1262.873468
+EDGE_SE2 1094 1095 0.025922 -0.007302 -0.593448 13559.452360 -41040.960104 0.000000 124333.371329 0.000000 984.609944
+EDGE_SE2 1095 1096 0.013621 -0.004396 -0.574854 32930.237834 -122414.831277 0.000000 455229.472232 0.000000 1007.997402
+EDGE_SE2 1096 1097 0.359533 -0.076883 -0.217554 11.145668 -5.017901 0.000000 739.746128 0.000000 1686.411461
+EDGE_SE2 1097 1098 0.655276 -0.022381 -0.058348 11.240870 -5.359644 0.000000 232.489049 0.000000 2231.942602
+EDGE_SE2 1098 1099 0.601562 -0.024926 -0.098508 11.973250 -15.083436 0.000000 275.001216 0.000000 2071.731935
+EDGE_SE2 1099 1100 0.019767 0.000659 0.359334 26235.559183 77565.286776 0.000000 229429.617699 0.000000 1352.968387
+EDGE_SE2 1100 1101 0.259176 0.070164 0.262689 11.115050 -2.328152 0.000000 1387.055621 0.000000 1568.004174
+EDGE_SE2 1101 1102 0.009767 -0.003058 -0.397627 8459.012576 -89410.542255 0.000000 946310.626975 0.000000 1279.845202
+EDGE_SE2 1102 1103 0.624811 -0.021021 -0.035899 11.112369 -0.554908 0.000000 255.864408 0.000000 2329.727795
+EDGE_SE2 1103 1104 0.653192 -0.005160 -0.029757 11.217748 -4.878085 0.000000 234.257657 0.000000 2357.602064
+EDGE_SE2 1104 1105 0.643770 -0.007193 -0.019886 11.128584 -2.005277 0.000000 241.242039 0.000000 2403.459167
+EDGE_SE2 1105 1106 0.496058 -0.003395 -0.027229 11.275339 -8.055101 0.000000 406.199361 0.000000 2369.220411
+EDGE_SE2 1106 1107 0.007526 0.002867 0.253134 18856.773417 -169404.055090 0.000000 1522787.727562 0.000000 1592.007032
+EDGE_SE2 1107 1108 0.625868 0.043204 0.005957 12.073074 -15.257830 0.000000 253.117791 0.000000 2470.479046
+EDGE_SE2 1108 1109 0.646003 -0.046291 -0.106175 11.383719 -7.866802 0.000000 238.127651 0.000000 2043.112734
+EDGE_SE2 1109 1110 0.614215 -0.005255 -0.051510 11.579361 -10.894385 0.000000 264.581538 0.000000 2261.065764
+EDGE_SE2 1110 1111 0.553199 -0.082221 -0.103442 11.711068 13.593477 0.000000 319.104424 0.000000 2053.246012
+EDGE_SE2 1111 1112 0.569389 0.118635 0.343250 16.481962 38.719218 0.000000 290.243375 0.000000 1385.563104
+EDGE_SE2 1112 1113 0.640195 -0.016890 -0.097447 12.284559 -16.483251 0.000000 242.648861 0.000000 2075.739728
+EDGE_SE2 1113 1114 0.617738 0.000372 0.015293 11.165263 3.685922 0.000000 262.000150 0.000000 2425.253974
+EDGE_SE2 1114 1115 0.584111 0.002651 -0.017913 11.253226 -6.328745 0.000000 292.947350 0.000000 2412.785348
+EDGE_SE2 1115 1116 0.648872 0.022176 0.034505 11.111138 0.077459 0.000000 237.232680 0.000000 2336.010662
+EDGE_SE2 1116 1117 0.098251 0.000884 -0.129855 209.328151 -1418.352583 0.000000 10160.208546 0.000000 1958.369267
+EDGE_SE2 1117 1118 0.002069 -0.000845 -0.611494 987546.746516 -4336045.136437 0.000000 19038602.480542 0.000000 962.681493
+EDGE_SE2 1118 1119 -0.002904 0.000748 -0.435035 368477.951626 -1990623.945676 0.000000 10754258.868008 0.000000 1213.989755
+EDGE_SE2 1119 1120 0.606241 -0.045059 -0.065468 11.130843 2.262698 0.000000 270.573321 0.000000 2202.212316
+EDGE_SE2 1120 1121 0.209582 -0.004500 -0.120622 33.301618 -223.063126 0.000000 2253.383418 0.000000 1990.772900
+EDGE_SE2 1121 1122 0.003037 -0.001969 -0.554282 3351.615045 159642.761466 0.000000 7629342.430661 0.000000 1034.857076
+EDGE_SE2 1122 1123 0.587650 -0.008795 0.015249 11.365183 8.406488 0.000000 289.256608 0.000000 2425.464195
+EDGE_SE2 1123 1124 0.579143 0.038116 0.096775 11.386604 8.868243 0.000000 296.584474 0.000000 2078.284141
+EDGE_SE2 1124 1125 0.646108 -0.002624 0.011822 11.168733 3.627591 0.000000 239.485218 0.000000 2441.921916
+EDGE_SE2 1125 1126 0.089655 0.001862 0.336774 1211.106301 3670.039910 0.000000 11235.483551 0.000000 1399.020340
+EDGE_SE2 1126 1127 -0.000544 0.000812 1.050094 84031228.496092 -41585087.528682 0.000000 20579500.003262 0.000000 594.829446
+EDGE_SE2 1127 1128 -0.002103 -0.000314 0.980680 12093669.618717 11006276.376659 0.000000 10016675.597149 0.000000 637.252248
+EDGE_SE2 1128 1129 0.011252 0.005103 1.008728 198520.561371 301067.442842 0.000000 456622.144090 0.000000 619.580502
+EDGE_SE2 1129 1130 0.583423 0.017793 0.012045 11.207158 -5.207167 0.000000 293.417741 0.000000 2440.845899
+EDGE_SE2 1130 1131 0.750481 -0.194337 -0.435123 16.183680 -27.603353 0.000000 161.320023 0.000000 1213.840879
+EDGE_SE2 1131 1132 0.640243 -0.002464 -0.021306 11.182068 -4.064051 0.000000 243.880425 0.000000 2396.780386
+EDGE_SE2 1132 1133 0.584277 -0.021867 -0.040363 11.113568 -0.831424 0.000000 292.516553 0.000000 2309.777849
+EDGE_SE2 1133 1134 0.266576 -0.000300 -0.098860 24.404478 -135.580323 0.000000 1393.907817 0.000000 2070.404863
+EDGE_SE2 1134 1135 0.009102 -0.002652 -0.559816 82791.558254 -291964.753439 0.000000 1029764.152962 0.000000 1027.527058
+EDGE_SE2 1135 1136 0.002258 -0.003305 -0.565768 971762.123150 2263140.796874 0.000000 5270709.266319 0.000000 1019.729968
+EDGE_SE2 1136 1137 0.306973 -0.042413 -0.186154 13.568352 -50.253896 0.000000 1038.871344 0.000000 1776.878994
+EDGE_SE2 1137 1138 0.654763 -0.011031 -0.017798 11.111312 -0.211469 0.000000 233.189098 0.000000 2413.330616
+EDGE_SE2 1138 1139 0.527941 0.000918 -0.077053 13.265063 -27.280422 0.000000 356.625570 0.000000 2155.092221
+EDGE_SE2 1139 1140 -0.002013 0.000175 -0.486547 3709493.048971 -8779833.609002 0.000000 20780669.837336 0.000000 1131.312847
+EDGE_SE2 1140 1141 0.002239 -0.000031 -0.555810 5310315.218372 -8816646.759236 0.000000 14638204.801536 0.000000 1032.825356
+EDGE_SE2 1141 1142 0.372375 -0.136555 -0.370794 11.343901 -12.055726 0.000000 635.453819 0.000000 1330.440997
+EDGE_SE2 1142 1143 0.629856 0.033762 0.085383 11.354434 7.641679 0.000000 251.102091 0.000000 2122.139741
+EDGE_SE2 1143 1144 0.612945 -0.010504 -0.034290 11.186135 -4.373095 0.000000 266.015507 0.000000 2336.981945
+EDGE_SE2 1144 1145 0.611105 -0.003802 -0.029142 11.245917 -5.880472 0.000000 267.628650 0.000000 2360.420642
+EDGE_SE2 1145 1146 0.609486 -0.000759 0.016125 11.188979 4.482263 0.000000 269.120272 0.000000 2421.284019
+EDGE_SE2 1146 1147 0.610275 0.036873 0.068649 11.128787 2.128847 0.000000 267.508800 0.000000 2189.121374
+EDGE_SE2 1147 1148 0.611337 -0.001965 0.012226 11.172242 3.959007 0.000000 267.506715 0.000000 2439.973063
+EDGE_SE2 1148 1149 0.074700 0.001638 0.503169 3846.534249 7344.890200 0.000000 14076.680961 0.000000 1106.431132
+EDGE_SE2 1149 1150 -0.006116 -0.002785 0.988331 626799.870889 997506.113526 0.000000 1587497.215478 0.000000 632.357453
+EDGE_SE2 1150 1151 0.014648 0.006739 0.987862 107400.301813 172549.549763 0.000000 277258.261675 0.000000 632.655875
+EDGE_SE2 1151 1152 0.009432 0.009802 1.036217 28480.057962 120720.157191 0.000000 511914.710091 0.000000 602.964704
+EDGE_SE2 1152 1153 0.010437 0.002034 0.996659 458897.357799 441929.724577 0.000000 425610.882022 0.000000 627.093176
+EDGE_SE2 1153 1154 0.277143 0.156011 0.537087 11.691675 23.815732 0.000000 988.073623 0.000000 1058.139946
+EDGE_SE2 1154 1155 0.634179 -0.005082 -0.053384 11.599710 -10.761566 0.000000 248.138569 0.000000 2253.027920
+EDGE_SE2 1155 1156 0.609122 -0.005838 0.006338 11.176606 4.113232 0.000000 269.430259 0.000000 2468.608751
+EDGE_SE2 1156 1157 0.580367 0.023367 0.106616 12.366206 18.881213 0.000000 295.153466 0.000000 2041.484648
+EDGE_SE2 1157 1158 0.608842 -0.050707 -0.133293 11.757739 -12.869932 0.000000 267.263428 0.000000 1946.505325
+EDGE_SE2 1158 1159 0.600995 -0.037895 -0.099499 11.464087 -9.658719 0.000000 275.409224 0.000000 2067.999033
+EDGE_SE2 1159 1160 0.637109 -0.021604 -0.142588 13.876030 -25.338115 0.000000 243.313239 0.000000 1914.964342
+EDGE_SE2 1160 1161 0.638306 -0.057065 -0.094949 11.118890 -1.344463 0.000000 243.484624 0.000000 2085.221653
+EDGE_SE2 1161 1162 0.639583 0.008532 0.053343 11.484272 9.323139 0.000000 244.042318 0.000000 2253.203316
+EDGE_SE2 1162 1163 0.646089 0.001306 -0.009750 11.142767 -2.689017 0.000000 239.527759 0.000000 2451.953812
+EDGE_SE2 1163 1164 0.642172 0.018842 0.080564 11.717339 11.822667 0.000000 241.677018 0.000000 2141.110196
+EDGE_SE2 1164 1165 0.530061 0.001899 -0.020695 11.314294 -8.367588 0.000000 355.709513 0.000000 2399.650727
+EDGE_SE2 1165 1166 0.004850 0.001220 0.493564 239307.954224 948357.988051 0.000000 3758451.305300 0.000000 1120.707645
+EDGE_SE2 1166 1167 0.000199 0.000971 0.944839 17209450.782475 -38137417.374455 0.000000 84515406.833935 0.000000 660.956228
+EDGE_SE2 1167 1168 0.004314 0.002779 0.911345 419892.583640 1190803.974162 0.000000 3377188.237646 0.000000 684.324107
+EDGE_SE2 1168 1169 0.046124 0.045485 0.829043 72.075115 1203.501414 0.000000 23769.649842 0.000000 747.295174
+EDGE_SE2 1169 1170 0.595970 0.008443 0.008952 11.118461 -1.409691 0.000000 281.483079 0.000000 2455.833943
+EDGE_SE2 1170 1171 0.643652 0.016020 0.034262 11.131351 2.158066 0.000000 241.208530 0.000000 2337.108483
+EDGE_SE2 1171 1172 0.608254 -0.008594 -0.059650 11.647713 -11.779607 0.000000 269.699888 0.000000 2226.461162
+EDGE_SE2 1172 1173 0.635753 0.004699 0.011813 11.115733 1.045017 0.000000 247.395251 0.000000 2441.965358
+EDGE_SE2 1173 1174 0.642740 -0.015092 -0.065577 11.519977 -9.706025 0.000000 241.521390 0.000000 2201.761802
+EDGE_SE2 1174 1175 0.635529 -0.015560 -0.030331 11.119207 -1.383209 0.000000 247.431148 0.000000 2354.975943
+EDGE_SE2 1175 1176 0.639892 -0.002591 -0.040430 11.419513 -8.473235 0.000000 243.910274 0.000000 2309.480375
+EDGE_SE2 1176 1177 0.631909 0.000862 0.005069 11.114395 0.886514 0.000000 250.429122 0.000000 2474.846416
+EDGE_SE2 1177 1178 0.638012 -0.011209 -0.043943 11.274194 -6.181646 0.000000 245.425622 0.000000 2293.963142
+EDGE_SE2 1178 1179 0.631478 0.010553 0.032543 11.171171 3.792944 0.000000 250.644522 0.000000 2344.896698
+EDGE_SE2 1179 1180 0.271033 0.000088 -0.003969 11.136010 -5.798071 0.000000 1361.277228 0.000000 2480.272525
+EDGE_SE2 1180 1181 0.006369 0.000562 0.838184 1136739.900794 1219876.425763 0.000000 1309117.124470 0.000000 739.881291
+EDGE_SE2 1181 1182 0.043362 0.037473 0.721003 13.218472 253.246510 0.000000 30444.337192 0.000000 844.066675
+EDGE_SE2 1182 1183 0.631233 0.006864 0.028504 11.185650 4.227407 0.000000 250.864920 0.000000 2363.349975
+EDGE_SE2 1183 1184 0.641740 0.028391 0.073043 11.303273 6.663120 0.000000 242.151864 0.000000 2171.229631
+EDGE_SE2 1184 1185 0.636568 -0.012623 -0.029018 11.131008 -2.164911 0.000000 246.663116 0.000000 2360.989552
+EDGE_SE2 1185 1186 0.637011 0.023759 0.069721 11.358319 7.617657 0.000000 245.847739 0.000000 2184.736002
+EDGE_SE2 1186 1187 0.658018 -0.006443 -0.033774 11.237521 -5.269863 0.000000 230.804698 0.000000 2339.315499
+EDGE_SE2 1187 1188 0.632380 0.009510 0.021371 11.120695 1.513079 0.000000 249.993325 0.000000 2396.475334
+EDGE_SE2 1188 1189 0.635906 -0.012539 0.021673 11.515314 9.760309 0.000000 246.794097 0.000000 2395.058778
+EDGE_SE2 1189 1190 0.298422 -0.000493 0.007995 11.214542 10.722954 0.000000 1122.783078 0.000000 2460.499340
+EDGE_SE2 1190 1191 -0.001378 -0.000184 0.920177 25978781.998107 25880314.470994 0.000000 25782242.304073 0.000000 678.043383
+EDGE_SE2 1191 1192 0.072942 0.060647 0.797518 130.506556 1145.096181 0.000000 10993.483679 0.000000 773.736998
+EDGE_SE2 1192 1193 0.612651 -0.026766 -0.132178 13.102394 -22.437131 0.000000 263.925490 0.000000 1950.341157
+EDGE_SE2 1193 1194 0.586582 0.016272 0.041820 11.166533 3.933966 0.000000 290.352323 0.000000 2303.321852
+EDGE_SE2 1194 1195 0.636169 0.007659 0.052000 11.487698 9.418662 0.000000 246.677289 0.000000 2258.959939
+EDGE_SE2 1195 1196 0.637063 -0.002513 -0.173199 17.787125 -39.066310 0.000000 239.717067 0.000000 1816.337880
+EDGE_SE2 1196 1197 0.631038 0.007284 0.010757 11.111259 -0.188614 0.000000 251.090831 0.000000 2447.070566
+EDGE_SE2 1197 1198 0.639335 0.035252 0.257911 20.557528 45.933130 0.000000 234.460604 0.000000 1579.938488
+EDGE_SE2 1198 1199 0.625974 -0.039991 -0.215702 16.676523 -36.355580 0.000000 248.600846 0.000000 1691.553532
+EDGE_SE2 1199 1200 0.642662 0.020896 0.068112 11.403588 8.210051 0.000000 241.573905 0.000000 2191.323116
+EDGE_SE2 1200 1201 0.632369 0.008692 0.054836 11.514278 9.806016 0.000000 249.617869 0.000000 2246.829525
+EDGE_SE2 1201 1202 0.636732 0.009332 0.021910 11.123506 1.708394 0.000000 246.587725 0.000000 2393.947989
+EDGE_SE2 1202 1203 0.605583 0.016194 -0.091218 14.730772 -30.544741 0.000000 268.864904 0.000000 2099.505256
+EDGE_SE2 1203 1204 0.604704 -0.076543 -0.148349 11.241024 -5.788533 0.000000 269.030303 0.000000 1895.798676
+EDGE_SE2 1204 1205 0.579744 0.012270 0.028212 11.125345 2.018565 0.000000 297.379849 0.000000 2364.692492
+EDGE_SE2 1205 1206 0.604024 0.022981 0.059672 11.234092 5.681316 0.000000 273.569799 0.000000 2226.368715
+EDGE_SE2 1206 1207 0.628833 -0.063349 -0.087865 11.148708 2.998873 0.000000 250.310531 0.000000 2112.467324
+EDGE_SE2 1207 1208 0.641879 0.018435 0.062871 11.381019 7.898378 0.000000 242.243300 0.000000 2212.987156
+EDGE_SE2 1208 1209 0.636239 0.001912 -0.003661 11.121595 -1.572688 0.000000 247.023047 0.000000 2481.795033
+EDGE_SE2 1209 1210 0.630195 0.024749 0.018688 11.212716 -4.940152 0.000000 251.306983 0.000000 2409.115535
+EDGE_SE2 1210 1211 0.632941 -0.047678 -0.070430 11.116473 1.127530 0.000000 248.202543 0.000000 2181.842838
+EDGE_SE2 1211 1212 0.633914 0.009606 0.052050 11.434554 8.761975 0.000000 248.470147 0.000000 2258.745224
+EDGE_SE2 1212 1213 0.635719 0.026579 0.075094 11.372749 7.851816 0.000000 246.746209 0.000000 2162.953249
+EDGE_SE2 1213 1214 0.748508 -0.025001 -0.220810 16.915079 -30.604005 0.000000 172.484342 0.000000 1677.427863
+EDGE_SE2 1214 1215 0.609440 0.015872 0.060134 11.410886 8.788375 0.000000 268.756514 0.000000 2224.428662
+EDGE_SE2 1215 1216 0.569604 0.086391 0.218432 12.447317 19.645507 0.000000 299.948223 0.000000 1683.981886
+EDGE_SE2 1216 1217 0.604098 -0.020910 -0.018798 11.176666 4.148410 0.000000 273.628656 0.000000 2408.595337
+EDGE_SE2 1217 1218 0.590246 0.008252 -0.050669 12.262477 -17.784784 0.000000 285.827155 0.000000 2264.686919
+EDGE_SE2 1218 1219 0.650992 0.006557 0.030598 11.205817 4.613431 0.000000 235.846718 0.000000 2353.755880
+EDGE_SE2 1219 1220 0.586496 0.026678 0.090738 11.682801 12.616550 0.000000 289.544235 0.000000 2101.353517
+EDGE_SE2 1220 1221 -0.001846 -0.000482 -0.452753 11628909.160981 -13576008.003722 0.000000 15849147.678198 0.000000 1184.558318
+EDGE_SE2 1221 1222 0.012937 -0.005157 -0.597307 24124.307745 -108858.692621 0.000000 491452.172995 0.000000 979.857795
+EDGE_SE2 1222 1223 0.011537 -0.003845 -0.559627 37585.948232 -154900.759550 0.000000 638583.281939 0.000000 1027.776110
+EDGE_SE2 1223 1224 0.574470 -0.089064 -0.182908 11.352146 -8.281702 0.000000 295.661931 0.000000 1786.644187
+EDGE_SE2 1224 1225 0.625700 0.003903 0.013764 11.124947 1.838454 0.000000 255.403355 0.000000 2432.575223
+EDGE_SE2 1225 1226 0.106504 -0.000109 -0.016731 13.283390 -138.281257 0.000000 8813.714781 0.000000 2418.398573
+EDGE_SE2 1226 1227 0.000000 0.000000 -0.000662 11.111282 -0.257444 0.000000 399.999830 0.000000 2496.693284
+EDGE_SE2 19 166 -2.459689 0.241111 0.252800 11.731352 1.696454 0.000000 15.751178 0.000000 1592.856013
+EDGE_SE2 19 172 1.067903 0.915786 0.149470 22.211594 -17.729393 0.000000 39.428022 0.000000 1892.102792
+EDGE_SE2 25 172 -2.539634 0.852630 -0.029860 11.348228 0.783018 0.000000 13.696833 0.000000 2357.130503
+EDGE_SE2 25 178 1.225223 0.672079 -0.102480 24.051651 -18.745770 0.000000 38.266385 0.000000 2056.830811
+EDGE_SE2 32 178 -2.020007 -0.239771 0.715180 15.237484 6.070047 0.000000 20.040376 0.000000 849.807581
+EDGE_SE2 32 183 -0.092559 0.424181 0.041600 515.079071 88.191252 0.000000 26.544031 0.000000 2304.294940
+EDGE_SE2 44 189 -2.265706 -0.570857 0.197720 11.128469 -0.353246 0.000000 18.300012 0.000000 1742.727183
+EDGE_SE2 44 195 1.302289 -0.133004 -0.005280 11.549680 4.530716 0.000000 57.916501 0.000000 2473.807626
+EDGE_SE2 50 195 -2.374379 -0.253682 0.216120 11.188114 0.699234 0.000000 17.460612 0.000000 1690.390904
+EDGE_SE2 50 201 1.291572 0.086248 -0.050700 11.777215 -5.648747 0.000000 59.014090 0.000000 2264.553285
+EDGE_SE2 50 203 2.550695 0.035722 -0.084650 11.152401 -0.417172 0.000000 15.326014 0.000000 2125.008969
+EDGE_SE2 61 203 -2.852494 0.122053 0.077870 11.127858 0.138148 0.000000 12.250754 0.000000 2151.826441
+EDGE_SE2 61 209 0.730780 0.072970 0.008890 12.538871 -15.710166 0.000000 183.975779 0.000000 2456.135792
+EDGE_SE2 67 209 -2.822142 0.138051 -0.004460 11.113900 0.062754 0.000000 12.522981 0.000000 2477.848305
+EDGE_SE2 67 220 0.783704 -1.176736 -1.412900 17.863537 -14.737201 0.000000 43.275118 0.000000 429.399329
+EDGE_SE2 81 220 -0.868391 -0.009825 -0.046880 11.522030 -7.053327 0.000000 132.179889 0.000000 2281.109865
+EDGE_SE2 81 226 2.836453 0.058719 0.049150 11.112174 0.037334 0.000000 12.422974 0.000000 2271.249469
+EDGE_SE2 87 226 -0.459640 0.184679 0.343830 185.785423 196.810927 0.000000 232.864045 0.000000 1384.367338
+EDGE_SE2 87 231 1.060624 0.863823 0.294010 34.429085 -29.740516 0.000000 94.681322 0.000000 4479.050905
+EDGE_SE2 94 231 -2.231597 0.316386 0.180250 23.930088 5.134954 0.000000 37.661225 0.000000 5384.101583
+EDGE_SE2 94 241 2.816677 0.483252 0.041400 22.259441 -0.288013 0.000000 24.450978 0.000000 6915.540303
+EDGE_SE2 101 241 -1.436886 0.314097 -0.098870 23.168499 8.096966 0.000000 91.505166 0.000000 6211.101543
+EDGE_SE2 101 247 2.168416 0.280309 -0.003870 22.564171 -2.567078 0.000000 41.493789 0.000000 7442.285250
+EDGE_SE2 107 247 -1.536762 0.375104 0.051050 26.954959 15.833327 0.000000 75.192472 0.000000 6789.136027
+EDGE_SE2 107 254 0.592787 -1.020976 -0.778000 30.649088 30.837091 0.000000 135.066803 0.000000 2372.453724
+EDGE_SE2 107 256 0.707309 -1.207974 -1.163740 23.417473 -9.695697 0.000000 100.872264 0.000000 1601.957964
+EDGE_SE2 107 258 0.976528 -2.202656 -1.227730 22.289493 -0.904508 0.000000 34.383996 0.000000 1511.249453
+EDGE_SE2 114 254 -0.931502 -0.024068 0.567580 77.556805 91.947180 0.000000 175.007037 0.000000 3052.121623
+EDGE_SE2 114 256 -0.723652 0.045801 0.181840 43.302820 84.297616 0.000000 359.313621 0.000000 5369.624220
+EDGE_SE2 114 258 0.306031 0.086093 0.117850 69.684517 -301.023297 0.000000 1931.422497 0.000000 6001.975262
+EDGE_SE2 121 266 0.737190 -0.017200 -0.118240 25.326151 -32.604829 0.000000 364.715589 0.000000 5997.789466
+EDGE_SE2 126 266 -1.480397 0.199141 0.062860 24.793867 12.913265 0.000000 87.064919 0.000000 6639.098888
+EDGE_SE2 126 272 2.350796 0.151313 0.025060 22.243466 -0.541415 0.000000 36.020406 0.000000 7137.772305
+EDGE_SE2 132 272 -1.375990 0.193564 -0.069560 22.622461 5.692420 0.000000 103.182984 0.000000 6556.181353
+EDGE_SE2 132 278 2.220707 0.319882 -0.000500 22.580601 -2.479176 0.000000 39.372548 0.000000 7492.505621
+EDGE_SE2 138 278 -1.378019 0.626427 0.016990 34.209796 25.223836 0.000000 75.297341 0.000000 7251.500784
+EDGE_SE2 138 284 2.391863 0.324204 -0.075755 22.750660 -2.473459 0.000000 33.799752 0.000000 6480.884307
+EDGE_SE2 151 284 -2.650853 -0.975732 1.454550 24.484817 1.146301 0.000000 22.802974 0.000000 1244.851357
+EDGE_SE2 151 291 -1.498500 0.364159 0.021790 26.317431 15.382872 0.000000 80.005044 0.000000 7183.530951
+EDGE_SE2 151 297 2.217429 -0.068852 -0.223460 22.895631 -3.456384 0.000000 39.962710 0.000000 5010.507463
+EDGE_SE2 19 305 -1.044094 0.006772 0.289080 17.951036 22.463977 0.000000 84.888274 0.000000 1504.458692
+EDGE_SE2 19 315 1.796874 2.231292 1.917670 11.894814 0.476141 0.000000 11.400392 0.000000 293.675468
+EDGE_SE2 19 337 1.676359 1.138847 2.369960 23.812750 -2.606854 0.000000 11.646135 0.000000 220.135719
+EDGE_SE2 19 342 2.451034 1.014379 -0.106190 11.820054 -1.302086 0.000000 13.502599 0.000000 2043.057325
+EDGE_SE2 19 1016 0.039741 0.374380 -2.852145 602.592071 -246.735273 0.000000 114.036309 0.000000 168.474698
+EDGE_SE2 25 315 -1.587705 2.017012 1.738340 12.043194 -1.708941 0.000000 14.244392 0.000000 333.399749
+EDGE_SE2 25 337 -1.901147 0.963583 2.190630 13.452340 -4.476777 0.000000 19.671370 0.000000 245.576678
+EDGE_SE2 25 342 -1.161097 0.702932 -0.285520 13.939899 10.682557 0.000000 51.452426 0.000000 1512.802847
+EDGE_SE2 25 367 0.878430 -0.159970 0.910020 100.995987 46.868336 0.000000 35.549493 0.000000 685.273881
+EDGE_SE2 25 374 2.840920 -0.557124 -0.601610 11.240233 -0.298749 0.000000 11.802326 0.000000 974.600130
+EDGE_SE2 25 1008 0.839778 0.868849 2.614245 65.217790 -13.300389 0.000000 14.380585 0.000000 191.383617
+EDGE_SE2 25 1010 0.208016 0.817490 -3.078070 128.288560 -37.883138 0.000000 23.358623 0.000000 150.324807
+EDGE_SE2 32 367 -1.650170 -1.061836 1.727680 23.555966 5.481395 0.000000 13.525417 0.000000 336.010748
+EDGE_SE2 32 374 -0.018221 0.098268 0.216050 10000.716890 -326.857444 0.000000 21.805806 0.000000 1690.585519
+EDGE_SE2 32 382 0.235335 2.451229 2.821510 16.224704 1.166981 0.000000 11.377430 0.000000 171.186695
+EDGE_SE2 32 387 0.993162 2.566664 0.274705 12.448992 -1.004261 0.000000 11.864945 0.000000 1538.582680
+EDGE_SE2 32 1003 0.362306 -0.196467 3.066965 108.121054 215.919400 0.000000 491.692649 0.000000 151.146840
+EDGE_SE2 32 1008 -2.427177 -0.386394 -2.851280 11.206045 0.712595 0.000000 16.460019 0.000000 168.550413
+EDGE_SE2 32 1010 -2.821790 -0.882420 -2.260410 11.209350 0.150567 0.000000 11.341881 0.000000 235.177395
+EDGE_SE2 44 437 0.696650 -2.771050 -0.205460 12.032017 0.446847 0.000000 11.327933 0.000000 1720.419675
+EDGE_SE2 44 454 -1.152851 -1.893499 1.516715 13.178717 3.850191 0.000000 18.280745 0.000000 394.704273
+EDGE_SE2 44 467 1.218289 1.232598 1.113140 13.331453 6.657638 0.000000 31.073862 0.000000 559.865191
+EDGE_SE2 44 494 2.154809 -0.649767 -0.306530 11.112721 -0.117867 0.000000 19.740180 0.000000 1464.539994
+EDGE_SE2 44 988 2.712903 -0.996652 3.047100 11.166944 0.211947 0.000000 11.915683 0.000000 152.634299
+EDGE_SE2 44 994 -0.892482 -0.642947 3.093485 38.865579 -34.860363 0.000000 54.896672 0.000000 149.194749
+EDGE_SE2 50 467 -2.756210 1.060141 1.334540 11.461044 -0.046083 0.000000 11.117180 0.000000 458.709115
+EDGE_SE2 50 494 -1.429190 -0.570621 -0.085130 17.367850 -12.471280 0.000000 35.969560 0.000000 2123.129418
+EDGE_SE2 50 500 2.268340 -0.490379 0.263640 12.680013 3.039151 0.000000 16.998309 0.000000 1565.644941
+EDGE_SE2 50 982 2.823043 -0.459737 -3.096925 11.157700 0.222838 0.000000 12.176961 0.000000 148.944310
+EDGE_SE2 50 988 -0.808543 -0.786485 -3.014685 35.481589 -32.415484 0.000000 54.227361 0.000000 155.108998
+EDGE_SE2 61 508 -1.449200 2.112314 1.477670 12.801726 -2.029955 0.000000 13.548517 0.000000 407.242490
+EDGE_SE2 61 522 -1.053664 -0.045704 0.099000 11.354883 4.375854 0.000000 89.660307 0.000000 2069.877405
+EDGE_SE2 61 528 2.466833 0.101003 -0.088240 11.198948 -0.676270 0.000000 16.317799 0.000000 2111.011691
+EDGE_SE2 61 976 1.165811 -0.076649 -3.054440 12.551016 9.349655 0.000000 71.820715 0.000000 152.082153
+EDGE_SE2 61 982 -2.503567 -0.322810 -2.934405 11.139618 0.360303 0.000000 15.665017 0.000000 161.503454
+EDGE_SE2 67 528 -1.085869 0.142906 -0.101590 11.172968 2.113193 0.000000 83.303853 0.000000 2060.155675
+EDGE_SE2 67 532 1.038480 -0.184540 -0.187270 11.121355 -0.898278 0.000000 89.877742 0.000000 1773.540133
+EDGE_SE2 67 556 0.875960 2.072499 -1.608750 12.194562 2.861649 0.000000 18.669404 0.000000 367.345805
+EDGE_SE2 67 564 0.934530 -0.521388 -1.425090 59.070878 -36.808963 0.000000 39.361868 0.000000 425.093327
+EDGE_SE2 67 567 1.078640 -1.127738 0.068640 28.794636 14.729412 0.000000 23.379907 0.000000 2189.158247
+EDGE_SE2 67 570 2.695842 -0.809094 0.129960 11.364179 0.564364 0.000000 12.369693 0.000000 1958.005326
+EDGE_SE2 67 965 0.918287 -0.079133 1.692110 113.199731 -21.468798 0.000000 15.625907 0.000000 344.948615
+EDGE_SE2 67 976 -2.389147 -0.017363 -3.067790 11.139434 0.425047 0.000000 17.489953 0.000000 151.085560
+EDGE_SE2 81 528 -2.540636 -1.571989 1.264430 11.150293 0.045554 0.000000 11.164073 0.000000 487.553422
+EDGE_SE2 81 532 -1.788049 0.441390 1.178750 29.071227 2.714944 0.000000 11.521516 0.000000 526.653783
+EDGE_SE2 81 564 -1.479377 0.271115 -0.059070 11.602730 4.003639 0.000000 43.715888 0.000000 2228.900474
+EDGE_SE2 81 567 -0.856391 0.288913 1.434660 118.478978 -20.563824 0.000000 15.049634 0.000000 421.758037
+EDGE_SE2 81 570 -0.839522 1.937122 1.495980 13.560960 -4.662733 0.000000 19.985567 0.000000 401.289509
+EDGE_SE2 81 575 -0.874481 2.499055 -2.998155 14.149112 0.594261 0.000000 11.227354 0.000000 156.394216
+EDGE_SE2 81 588 2.585410 -0.398590 0.032990 11.230814 0.636285 0.000000 14.493300 0.000000 2342.867749
+EDGE_SE2 81 959 1.715988 -0.147087 2.880085 11.804020 -3.896236 0.000000 33.019679 0.000000 166.057104
+EDGE_SE2 81 965 -1.915695 0.345142 3.058130 11.248005 1.439837 0.000000 26.255228 0.000000 151.805707
+EDGE_SE2 87 588 -0.567044 -0.325829 0.327670 19.376959 -42.100418 0.000000 225.541056 0.000000 1418.272639
+EDGE_SE2 87 597 1.033167 2.497995 1.747590 11.858143 1.168127 0.000000 12.937699 0.000000 331.158689
+EDGE_SE2 87 604 1.169979 2.733059 -1.279630 11.194520 0.099906 0.000000 11.230777 0.000000 481.073330
+EDGE_SE2 87 953 1.577352 0.448961 -2.823050 11.155436 1.074029 0.000000 37.135844 0.000000 171.048808
+EDGE_SE2 87 959 -1.472035 -0.337676 -3.108420 12.306884 -6.140766 0.000000 42.646361 0.000000 148.112032
+EDGE_SE2 94 597 -2.073375 1.943112 1.633830 11.708877 -0.635533 0.000000 11.786797 0.000000 360.383193
+EDGE_SE2 94 604 -1.910764 2.161126 -1.393390 11.355872 -0.402293 0.000000 11.772326 0.000000 436.428461
+EDGE_SE2 94 616 -0.567925 0.985809 1.728270 19.547380 -22.065015 0.000000 68.822033 0.000000 335.865437
+EDGE_SE2 94 632 -0.258230 -0.057031 -0.961010 1222.393668 -501.336231 0.000000 218.608540 0.000000 650.100338
+EDGE_SE2 94 637 2.180403 0.487495 0.048180 11.371804 -1.502621 0.000000 19.772123 0.000000 2275.455104
+EDGE_SE2 94 947 1.819562 0.355845 -2.812985 11.439117 2.406258 0.000000 28.763471 0.000000 171.952995
+EDGE_SE2 94 953 -1.765303 -0.154451 -2.936810 11.396122 2.414195 0.000000 31.560619 0.000000 161.306214
+EDGE_SE2 101 637 -2.066317 0.407256 -0.092090 11.230841 1.163903 0.000000 22.425529 0.000000 2096.153815
+EDGE_SE2 101 642 0.702540 0.058990 -0.158060 22.012272 -44.195550 0.000000 190.288971 0.000000 1864.137257
+EDGE_SE2 101 645 1.268565 0.117224 1.302975 55.348130 16.649223 0.000000 17.377280 0.000000 471.369465
+EDGE_SE2 101 657 0.970735 1.275733 -1.200065 31.327289 12.383774 0.000000 18.697009 0.000000 516.498549
+EDGE_SE2 101 663 2.721944 0.234701 0.154665 11.121870 0.156475 0.000000 13.386764 0.000000 1875.114422
+EDGE_SE2 101 665 2.743644 0.343689 1.484400 12.992900 0.403085 0.000000 11.197453 0.000000 405.039117
+EDGE_SE2 101 939 1.736598 0.040097 -3.139770 11.121070 -0.468281 0.000000 33.131371 0.000000 145.877255
+EDGE_SE2 101 944 -1.229619 0.290529 3.034680 11.913468 6.379852 0.000000 61.839764 0.000000 153.575457
+EDGE_SE2 101 947 -2.442020 0.327348 -2.953255 11.646767 1.607820 0.000000 15.937136 0.000000 159.966957
+EDGE_SE2 101 1138 -0.044980 -2.128090 1.406340 11.334711 -1.549412 0.000000 21.847605 0.000000 431.743719
+EDGE_SE2 101 1188 1.043367 -1.716987 3.078145 20.296004 6.412523 0.000000 15.588077 0.000000 150.319256
+EDGE_SE2 107 642 -2.988279 0.073654 -0.103140 11.111606 -0.006296 0.000000 11.191151 0.000000 2054.370375
+EDGE_SE2 107 645 -2.426303 0.162871 1.357895 16.787995 0.834037 0.000000 11.233646 0.000000 449.666954
+EDGE_SE2 107 663 -0.981564 0.359950 0.209585 33.867694 36.211234 0.000000 68.731953 0.000000 1708.704657
+EDGE_SE2 107 665 -0.965880 0.469964 1.539320 74.030616 -28.201297 0.000000 23.751280 0.000000 387.708339
+EDGE_SE2 107 680 -1.101202 1.597727 -1.082720 11.315853 -1.766538 0.000000 26.353031 0.000000 576.339299
+EDGE_SE2 107 683 -0.373238 0.237253 -0.978670 91.473664 -183.671027 0.000000 430.896755 0.000000 638.547590
+EDGE_SE2 107 704 -0.174419 -0.744617 -2.364960 56.805507 -72.228521 0.000000 125.281768 0.000000 220.790405
+EDGE_SE2 107 714 -0.001585 -1.518738 0.040750 43.298168 -1.345998 0.000000 11.167398 0.000000 2308.060399
+EDGE_SE2 107 730 1.719547 -1.998733 -2.849795 13.843772 1.215931 0.000000 11.652154 0.000000 168.680442
+EDGE_SE2 107 929 0.482300 -2.592003 1.960350 11.247596 0.654505 0.000000 14.249748 0.000000 285.268546
+EDGE_SE2 107 935 -0.294578 0.372182 2.191385 12.146819 -21.145445 0.000000 442.825321 0.000000 245.460450
+EDGE_SE2 107 939 -1.954743 0.111552 -3.084850 11.304032 1.688716 0.000000 25.893149 0.000000 149.826206
+EDGE_SE2 107 1147 -0.324254 -1.481983 0.140150 39.532534 -10.553850 0.000000 15.030118 0.000000 1923.162692
+EDGE_SE2 107 1150 0.364219 -1.279939 1.435915 18.388124 -16.646666 0.000000 49.191505 0.000000 421.323458
+EDGE_SE2 114 663 -2.629135 -1.250276 1.555165 11.663410 0.273309 0.000000 11.246360 0.000000 382.914669
+EDGE_SE2 114 665 -2.732868 -1.210420 2.884900 11.143210 -0.040214 0.000000 11.161493 0.000000 165.645759
+EDGE_SE2 114 683 -2.373686 -0.684712 0.366910 11.150086 0.451690 0.000000 16.345825 0.000000 1338.012489
+EDGE_SE2 114 704 -1.372213 -0.710183 -1.019380 41.720375 -2.264013 0.000000 11.278569 0.000000 613.061308
+EDGE_SE2 114 714 -0.579045 -0.714588 1.386330 35.416827 44.860054 0.000000 93.907456 0.000000 439.014644
+EDGE_SE2 114 730 0.273187 0.855886 -1.504215 26.282898 38.481991 0.000000 108.717525 0.000000 398.654506
+EDGE_SE2 114 929 0.575175 -0.482602 -2.977255 107.010292 82.154133 0.000000 81.490248 0.000000 158.042201
+EDGE_SE2 114 935 -2.487642 -0.577907 -2.746220 11.227888 0.692283 0.000000 15.215150 0.000000 178.136720
+EDGE_SE2 114 1147 -0.686929 -1.020901 1.485730 24.072771 23.324553 0.000000 53.083724 0.000000 404.605797
+EDGE_SE2 114 1150 -0.730123 -0.304695 2.781495 80.988104 -74.193686 0.000000 89.888157 0.000000 174.828760
+EDGE_SE2 114 1158 1.965070 -0.055808 0.083960 11.296704 1.644922 0.000000 25.690196 0.000000 2127.715200
+EDGE_SE2 114 1175 2.570804 -0.255481 2.913020 11.175699 -0.495876 0.000000 14.918247 0.000000 163.273564
+EDGE_SE2 121 754 -0.176774 -0.090674 -0.104160 764.277342 -1154.350823 0.000000 1780.343146 0.000000 2050.576559
+EDGE_SE2 121 759 2.795658 -0.372882 -0.047990 11.121537 0.122936 0.000000 12.560684 0.000000 2276.280256
+EDGE_SE2 121 923 -0.359940 -0.158411 2.816780 299.677751 -316.410365 0.000000 358.051835 0.000000 171.611249
+EDGE_SE2 121 1158 -1.765259 0.015433 0.094390 11.333442 2.148138 0.000000 31.866199 0.000000 2087.352405
+EDGE_SE2 121 1164 1.939145 -0.416391 -0.071910 11.388217 1.971985 0.000000 25.144479 0.000000 2175.822000
+EDGE_SE2 121 1175 -1.157476 -0.177912 2.923450 19.220682 -20.867733 0.000000 64.808438 0.000000 162.406633
+EDGE_SE2 126 754 -2.366181 -0.037747 0.076940 11.136170 0.410365 0.000000 17.831325 0.000000 2155.544499
+EDGE_SE2 126 759 0.608470 0.220030 0.133110 21.370901 -47.238010 0.000000 228.603826 0.000000 1947.134106
+EDGE_SE2 126 762 1.256487 0.430359 1.248090 39.878585 21.991658 0.000000 27.922912 0.000000 494.666638
+EDGE_SE2 126 923 -2.534151 -0.137367 2.997880 11.281716 -0.850942 0.000000 15.355440 0.000000 156.415757
+EDGE_SE2 126 1164 -0.226200 0.022965 0.109190 94.980319 392.781106 0.000000 1850.606209 0.000000 2032.020653
+EDGE_SE2 132 762 -2.439040 0.574751 1.153470 15.760986 0.874518 0.000000 11.275585 0.000000 539.091342
+EDGE_SE2 132 778 -1.013501 1.621706 1.561210 15.810999 -7.362314 0.000000 22.644082 0.000000 381.109374
+EDGE_SE2 132 792 -0.882133 1.768911 -1.797920 16.975203 -7.109142 0.000000 19.729650 0.000000 319.351840
+EDGE_SE2 132 800 1.214689 0.372313 0.005900 15.310892 -13.996183 0.000000 57.754774 0.000000 2470.759036
+EDGE_SE2 132 907 2.246094 -0.166035 -3.063890 11.307039 1.283425 0.000000 19.518199 0.000000 151.375685
+EDGE_SE2 132 911 0.287430 -0.091199 2.898905 15.641604 70.080974 0.000000 1095.174761 0.000000 164.457860
+EDGE_SE2 132 1084 -0.744736 -2.350749 -1.849821 11.115227 0.148119 0.000000 16.441489 0.000000 307.825761
+EDGE_SE2 138 800 -2.384799 0.661256 0.023390 11.548813 1.446295 0.000000 15.890090 0.000000 2387.028865
+EDGE_SE2 138 806 1.314158 0.976356 0.186155 16.125723 -10.306715 0.000000 32.294877 0.000000 1776.876918
+EDGE_SE2 138 821 1.339602 0.836157 -1.728640 27.615689 14.355051 0.000000 23.596586 0.000000 335.774357
+EDGE_SE2 138 823 1.391787 0.830084 -0.201680 23.357993 -13.427129 0.000000 25.832230 0.000000 1731.260189
+EDGE_SE2 138 903 0.257877 0.385262 2.468460 462.130945 37.644489 0.000000 14.253118 0.000000 207.810089
+EDGE_SE2 138 904 0.211460 0.361905 2.918540 518.619452 -160.188745 0.000000 61.672712 0.000000 162.813885
+EDGE_SE2 138 907 -1.344137 0.141028 -3.046400 12.828819 8.485440 0.000000 53.029004 0.000000 152.687113
+EDGE_SE2 151 828 -2.783661 1.064375 1.529770 11.244135 -0.044701 0.000000 11.126133 0.000000 390.641099
+EDGE_SE2 151 847 -2.892269 0.357584 -1.720550 11.773808 0.017727 0.000000 11.111585 0.000000 337.774286
+EDGE_SE2 151 855 0.421564 -0.036975 -0.072980 11.226261 7.937694 0.000000 558.283669 0.000000 2171.484605
+EDGE_SE2 151 895 -0.308314 0.072387 -2.940720 183.554391 374.539119 0.000000 824.593387 0.000000 160.986275
+EDGE_SE2 151 897 -0.653297 -0.340780 -2.145820 53.093226 74.186112 0.000000 142.204535 0.000000 252.622641
+EDGE_SE2 151 1029 2.658346 -1.322835 -1.612160 11.303644 -0.086066 0.000000 11.149585 0.000000 366.387340
+EDGE_SE2 157 297 -1.431635 -0.047784 -0.192100 12.991577 -8.198575 0.000000 46.855781 0.000000 1759.197636
+EDGE_SE2 157 305 2.323872 -0.569035 0.026110 11.551318 1.614103 0.000000 17.029536 0.000000 2374.390623
+EDGE_SE2 157 1029 -0.951615 -1.287326 -1.580800 20.706819 13.256279 0.000000 29.424395 0.000000 375.345582
+EDGE_SE2 157 1217 -0.999593 -2.295582 1.588120 11.945029 1.827929 0.000000 15.117890 0.000000 373.225399
+EDGE_SE2 163 297 -0.152489 -1.643361 1.294160 11.969142 -4.607638 0.000000 35.854192 0.000000 474.998898
+EDGE_SE2 163 305 0.683999 2.054722 1.512370 11.800954 2.562970 0.000000 20.633308 0.000000 396.070787
+EDGE_SE2 163 1029 1.123157 -1.269718 -0.094540 22.165118 11.817460 0.000000 23.744753 0.000000 2086.780326
+EDGE_SE2 163 1217 2.123761 -1.402656 3.074380 12.166102 1.857716 0.000000 14.382333 0.000000 150.597217
+EDGE_SE2 166 297 -2.448623 -0.097923 -0.181930 11.379485 -1.189522 0.000000 16.383459 0.000000 1789.602165
+EDGE_SE2 166 305 1.311990 -0.580954 0.036280 18.290583 14.744491 0.000000 41.391889 0.000000 2328.015008
+EDGE_SE2 166 1016 2.453320 -0.496114 -3.104945 11.376696 1.103524 0.000000 15.696336 0.000000 148.362881
+EDGE_SE2 166 1029 -1.956023 -1.332520 -1.570630 15.716267 3.136091 0.000000 13.246776 0.000000 378.321363
+EDGE_SE2 172 305 -2.223813 -0.584373 0.139610 11.218103 -0.907468 0.000000 18.807912 0.000000 1924.985691
+EDGE_SE2 172 315 0.916741 1.192284 1.768200 29.887371 16.398688 0.000000 25.433291 0.000000 326.245913
+EDGE_SE2 172 328 0.389353 2.701274 -1.418880 11.306838 0.643966 0.000000 13.229838 0.000000 427.278816
+EDGE_SE2 172 337 0.634889 0.129966 2.220490 195.557030 -88.592401 0.000000 53.663494 0.000000 241.043874
+EDGE_SE2 172 342 1.382392 -0.108475 -0.255660 12.384043 -7.102031 0.000000 50.735268 0.000000 1585.608223
+EDGE_SE2 172 1010 2.747473 0.046909 -3.048210 11.123505 0.162102 0.000000 13.231218 0.000000 152.550608
+EDGE_SE2 172 1016 -1.097321 -0.382262 -3.001615 13.480215 -11.980076 0.000000 71.691915 0.000000 156.123881
+EDGE_SE2 178 342 -2.376956 -0.213431 -0.183040 11.578392 -1.671546 0.000000 17.090523 0.000000 1786.245513
+EDGE_SE2 178 367 -0.259854 -0.863160 1.012500 18.840526 -28.383170 0.000000 115.336891 0.000000 617.260137
+EDGE_SE2 178 374 1.732968 -1.057467 -0.499130 11.142356 0.640290 0.000000 24.232266 0.000000 1112.401122
+EDGE_SE2 178 1003 1.826983 -1.529516 2.351785 11.166956 -0.600028 0.000000 17.558198 0.000000 222.529516
+EDGE_SE2 178 1008 -0.403552 0.156306 2.716725 12.710306 -28.871300 0.000000 532.343545 0.000000 180.975206
+EDGE_SE2 178 1010 -1.026746 0.040588 -2.975590 14.592518 16.700937 0.000000 91.228510 0.000000 158.174631
+EDGE_SE2 183 367 -1.618063 -1.419954 1.686080 18.191945 4.896376 0.000000 14.496941 0.000000 346.499109
+EDGE_SE2 183 374 0.060720 -0.328723 0.174450 894.828841 7.251305 0.000000 11.170611 0.000000 1812.470490
+EDGE_SE2 183 382 0.411911 2.011657 2.779910 23.397894 1.979206 0.000000 11.429930 0.000000 174.975438
+EDGE_SE2 183 387 1.173883 2.095476 0.233105 14.481439 -3.100632 0.000000 13.963629 0.000000 1644.144968
+EDGE_SE2 183 1003 0.428660 -0.639029 3.025365 102.305125 77.922908 0.000000 77.694205 0.000000 154.287027
+EDGE_SE2 183 1008 -2.366308 -0.712782 -2.892880 11.121230 -0.230529 0.000000 16.363269 0.000000 164.967341
+EDGE_SE2 189 400 -1.948699 2.200613 -1.116370 11.144116 -0.119102 0.000000 11.540899 0.000000 558.157565
+EDGE_SE2 189 414 -0.254807 -1.783532 -1.508360 11.922188 3.913799 0.000000 29.996898 0.000000 397.338159
+EDGE_SE2 189 454 0.831360 -1.515476 1.318995 21.578630 -11.156350 0.000000 23.001623 0.000000 464.879365
+EDGE_SE2 189 994 1.332308 -0.340434 2.895765 11.111898 0.181350 0.000000 52.882967 0.000000 164.723074
+EDGE_SE2 195 437 -0.591701 -2.641206 -0.200180 13.648824 -0.051289 0.000000 11.112148 0.000000 1735.590395
+EDGE_SE2 195 467 -0.091210 1.365140 1.118420 21.523802 -18.224556 0.000000 43.008191 0.000000 557.077827
+EDGE_SE2 195 484 0.655807 2.573505 -2.009240 11.219291 -0.565783 0.000000 14.070164 0.000000 276.074540
+EDGE_SE2 195 494 0.855236 -0.512254 -0.301250 16.102937 20.540136 0.000000 95.628725 0.000000 1476.449250
+EDGE_SE2 195 988 1.415155 -0.856188 3.052380 16.022409 10.041613 0.000000 31.642140 0.000000 152.236812
+EDGE_SE2 195 994 -2.192048 -0.521524 3.098765 11.750475 -2.253964 0.000000 19.057069 0.000000 148.810613
+EDGE_SE2 201 494 -2.683977 -0.793909 -0.034430 11.276756 -0.496479 0.000000 12.599187 0.000000 2336.349413
+EDGE_SE2 201 500 1.004735 -0.526385 0.314340 45.186413 33.298498 0.000000 43.650514 0.000000 1447.186686
+EDGE_SE2 201 982 1.557172 -0.467671 -3.046225 14.919173 9.340266 0.000000 34.020554 0.000000 152.700298
+EDGE_SE2 201 988 -2.053188 -0.978041 -2.963985 11.683303 -2.092334 0.000000 18.762142 0.000000 159.102109
+EDGE_SE2 203 500 -0.236863 -0.548090 0.348290 153.663942 -134.464803 0.000000 137.946777 0.000000 1375.223806
+EDGE_SE2 203 508 1.553867 1.875066 1.399800 12.536000 2.482853 0.000000 15.437455 0.000000 434.100125
+EDGE_SE2 203 522 1.780329 -0.307182 0.021130 11.822071 3.657498 0.000000 29.926926 0.000000 2397.606666
+EDGE_SE2 203 982 0.313263 -0.470658 -3.012275 253.866414 119.649456 0.000000 70.084044 0.000000 155.295388
+EDGE_SE2 209 508 -2.161765 2.058644 1.468780 11.180293 -0.053576 0.000000 11.152602 0.000000 410.180706
+EDGE_SE2 209 522 -1.785428 -0.102806 0.090110 11.132515 0.656456 0.000000 31.244975 0.000000 2103.775347
+EDGE_SE2 209 528 1.736233 0.012599 -0.097130 11.350617 -2.286079 0.000000 32.931671 0.000000 2076.939411
+EDGE_SE2 209 976 0.433683 -0.153481 -3.063330 87.280240 171.295909 0.000000 396.336584 0.000000 151.417412
+EDGE_SE2 220 528 -1.597199 -1.638814 1.311310 13.034804 3.414597 0.000000 17.172093 0.000000 467.976033
+EDGE_SE2 220 532 -0.939792 0.407621 1.225630 94.950637 -5.379789 0.000000 11.456320 0.000000 504.700895
+EDGE_SE2 220 564 -0.623480 0.251998 -0.012190 38.845567 71.101745 0.000000 193.391889 0.000000 2440.146629
+EDGE_SE2 220 567 -0.002013 0.298972 1.481540 21.284937 -105.664807 0.000000 1108.540123 0.000000 405.973278
+EDGE_SE2 220 570 -0.062402 1.946160 1.542860 11.165977 -0.913492 0.000000 26.320380 0.000000 386.629607
+EDGE_SE2 220 575 -0.123656 2.505837 -2.951275 15.792523 -0.664538 0.000000 11.205444 0.000000 160.127317
+EDGE_SE2 220 959 2.587973 -0.016000 2.926965 11.274656 -0.773198 0.000000 14.766597 0.000000 162.116000
+EDGE_SE2 220 965 -1.062787 0.305497 3.105010 15.212918 16.523642 0.000000 77.674651 0.000000 148.358205
+EDGE_SE2 226 231 1.660221 0.126920 -0.049820 11.505996 -3.114430 0.000000 35.674411 0.000000 2268.351350
+EDGE_SE2 226 588 -0.273207 -0.444423 -0.016160 274.806053 -156.291042 0.000000 103.744249 0.000000 2421.117227
+EDGE_SE2 226 597 2.185242 1.674700 1.403760 12.078039 1.038206 0.000000 12.225850 0.000000 432.671013
+EDGE_SE2 226 953 2.006857 -0.437847 3.116305 11.557944 2.329386 0.000000 23.254435 0.000000 147.545120
+EDGE_SE2 226 959 -1.129223 -0.150509 2.830935 23.235807 -25.544568 0.000000 64.928953 0.000000 170.345385
+EDGE_SE2 923 1175 0.749610 0.273000 0.106670 19.536607 -34.047517 0.000000 148.697481 0.000000 2041.285424
+EDGE_SE2 929 1175 -2.005899 0.102421 -0.392910 12.648561 -4.320259 0.000000 23.251108 0.000000 1288.528106
+EDGE_SE2 939 1188 0.696432 1.755817 -0.065270 26.430265 -4.946684 0.000000 12.708437 0.000000 2203.031036
+EDGE_SE2 1029 1217 1.008685 -0.037889 -3.114265 11.476877 5.630362 0.000000 97.781127 0.000000 147.691473
+EDGE_SE2 1044 1217 2.098504 -0.838430 0.479890 15.976239 4.188481 0.000000 14.717054 0.000000 1141.513725
+EDGE_SE2 1050 1210 -0.300235 -2.565672 1.536560 11.137270 0.317303 0.000000 14.960021 0.000000 388.552520
+EDGE_SE2 1050 1217 0.231465 1.668290 1.559140 11.493589 3.014437 0.000000 34.868922 0.000000 381.726156
+EDGE_SE2 1056 1217 2.128743 -0.472375 -0.931160 15.353750 -4.908186 0.000000 16.789250 0.000000 670.352902
+EDGE_SE2 1061 1210 1.269232 -1.441319 -2.909610 23.568115 6.644624 0.000000 14.655385 0.000000 163.558506
+EDGE_SE2 1075 1210 -1.662329 0.436026 -1.599840 32.701727 -4.997844 0.000000 12.268023 0.000000 369.868006
+EDGE_SE2 1084 1210 2.070374 1.896269 1.836205 12.355692 0.641825 0.000000 11.442098 0.000000 310.788312
+EDGE_SE2 1088 1210 0.609503 -1.485166 0.536770 38.204841 -4.021013 0.000000 11.707874 0.000000 1058.576530
+EDGE_SE2 1093 1210 -0.233452 -0.529583 1.494360 42.853783 90.090527 0.000000 266.801722 0.000000 401.810926
+EDGE_SE2 1098 1210 -0.378280 -0.172442 -2.937025 38.903093 -122.470929 0.000000 550.803768 0.000000 161.288572
+EDGE_SE2 1138 1188 0.583736 -1.006358 1.671805 21.764394 -23.563240 0.000000 63.228969 0.000000 350.211491
+EDGE_SE2 1147 1188 -2.232188 0.113982 2.992915 11.195782 -0.864255 0.000000 19.932721 0.000000 156.804966
+EDGE_SE2 1150 1188 -0.789302 2.834301 1.697150 11.120354 -0.063189 0.000000 11.543094 0.000000 343.660651
+EDGE_SE2 1158 1175 0.586855 -0.249767 2.829060 13.000858 20.975969 0.000000 243.941877 0.000000 170.512281
diff --git a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb
deleted file mode 100644
index 632bf57992..0000000000
--- a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb
+++ /dev/null
@@ -1,657 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [],
- "source": [
- "import numpy as np\n",
- "import copy\n",
- "import math\n",
- "import itertools\n",
- "import numpy as np \n",
- "import cvxpy as cp\n",
- "import matplotlib.pyplot as plt\n",
- "from graph_based_slam import calc_rotational_matrix, calc_jacobian, cal_observation_sigma, \\\n",
- " calc_input, observation, motion_model, Edge, pi_2_pi\n",
- "\n",
- "%matplotlib inline\n",
- "np.set_printoptions(precision=3, suppress=True)\n",
- "np.random.seed(0)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Introduction\n",
- "\n",
- "In contrast to the probabilistic approaches for solving SLAM, such as EKF, UKF, particle filters, and so on, the graph technique formulates the SLAM as an optimization problem. It is mostly used to solve the full SLAM problem in an offline fashion, i.e. optimize all the poses of the robot after the path has been traversed. However, some variants are availble that uses graph-based approaches to perform online estimation or to solve for a subset of the poses.\n",
- "\n",
- "GraphSLAM uses the motion information as well as the observations of the environment to create least square problem that can be solved using standard optimization techniques.\n",
- "\n",
- "### Minimal Example\n",
- "The following example illustrates the main idea behind graphSLAM. \n",
- "A simple case of a 1D robot is considered that can only move in 1 direction. The robot is commanded to move forward with a control input $u_t=1$, however, the motion is not perfect and the measured odometry will deviate from the true path. At each timestep the robot can observe its environment, for this simple case as well, there is only a single landmark at coordinates $x=3$. The measured observations are the range between the robot and landmark. These measurements are also subjected to noise. No bearing information is required since this is a 1D problem.\n",
- "\n",
- "To solve this, graphSLAM creates what is called as the system information matrix $\\Omega$ also referred to as $H$ and the information vector $\\xi$ also known as $b$. The entries are created based on the information of the motion and the observation."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 2,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- },
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "The determinant of H: 0.0\n",
- "The determinant of H after anchoring constraint: 18.75\n",
- "Running graphSLAM ...\n",
- "Odometry values after optimzation: \n",
- " [[0. ]\n",
- " [0.947]\n",
- " [1.939]]\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "R = 0.2\n",
- "Q = 0.2\n",
- "N = 3\n",
- "graphics_radius = 0.1\n",
- "\n",
- "odom = np.empty((N,1))\n",
- "obs = np.empty((N,1))\n",
- "x_true = np.empty((N,1))\n",
- "\n",
- "landmark = 3\n",
- "# Simulated readings of odometry and observations\n",
- "x_true[0], odom[0], obs[0] = 0.0, 0.0, 2.9\n",
- "x_true[1], odom[1], obs[1] = 1.0, 1.5, 2.0\n",
- "x_true[2], odom[2], obs[2] = 2.0, 2.4, 1.0\n",
- "\n",
- "hxDR = copy.deepcopy(odom)\n",
- "# Visualization\n",
- "plt.plot(landmark,0, '*k', markersize=30)\n",
- "for i in range(N):\n",
- " plt.plot(odom[i], 0, '.', markersize=50, alpha=0.8, color='steelblue')\n",
- " plt.plot([odom[i], odom[i] + graphics_radius],\n",
- " [0,0], 'r')\n",
- " plt.text(odom[i], 0.02, \"X_{}\".format(i), fontsize=12)\n",
- " plt.plot(obs[i]+odom[i],0,'.', markersize=25, color='brown')\n",
- " plt.plot(x_true[i],0,'.g', markersize=20)\n",
- "plt.grid() \n",
- "plt.show()\n",
- "\n",
- "\n",
- "# Defined as a function to facilitate iteration\n",
- "def get_H_b(odom, obs):\n",
- " \"\"\"\n",
- " Create the information matrix and information vector. This implementation is \n",
- " based on the concept of virtual measurement i.e. the observations of the\n",
- " landmarks are converted into constraints (edges) between the nodes that\n",
- " have observed this landmark.\n",
- " \"\"\"\n",
- " measure_constraints = {}\n",
- " omegas = {}\n",
- " zids = list(itertools.combinations(range(N),2))\n",
- " H = np.zeros((N,N))\n",
- " b = np.zeros((N,1))\n",
- " for (t1, t2) in zids:\n",
- " x1 = odom[t1]\n",
- " x2 = odom[t2]\n",
- " z1 = obs[t1]\n",
- " z2 = obs[t2]\n",
- " \n",
- " # Adding virtual measurement constraint\n",
- " measure_constraints[(t1,t2)] = (x2-x1-z1+z2)\n",
- " omegas[(t1,t2)] = (1 / (2*Q))\n",
- " \n",
- " # populate system's information matrix and vector\n",
- " H[t1,t1] += omegas[(t1,t2)]\n",
- " H[t2,t2] += omegas[(t1,t2)]\n",
- " H[t2,t1] -= omegas[(t1,t2)]\n",
- " H[t1,t2] -= omegas[(t1,t2)]\n",
- "\n",
- " b[t1] += measure_constraints[(t1,t2)]\n",
- " b[t2] -= measure_constraints[(t1,t2)]\n",
- "\n",
- " return H, b\n",
- "\n",
- "\n",
- "H, b = get_H_b(odom, obs)\n",
- "print(\"The determinant of H: \", np.linalg.det(H))\n",
- "H[0,0] += 1 # np.inf ?\n",
- "print(\"The determinant of H after anchoring constraint: \", np.linalg.det(H))\n",
- "\n",
- "for i in range(5):\n",
- " H, b = get_H_b(odom, obs)\n",
- " H[(0,0)] += 1\n",
- " \n",
- " # Recover the posterior over the path\n",
- " dx = np.linalg.inv(H) @ b\n",
- " odom += dx\n",
- " # repeat till convergence\n",
- "print(\"Running graphSLAM ...\") \n",
- "print(\"Odometry values after optimzation: \\n\", odom)\n",
- "\n",
- "plt.figure()\n",
- "plt.plot(x_true, np.zeros(x_true.shape), '.', markersize=20, label='Ground truth')\n",
- "plt.plot(odom, np.zeros(x_true.shape), '.', markersize=20, label='Estimation')\n",
- "plt.plot(hxDR, np.zeros(x_true.shape), '.', markersize=20, label='Odom')\n",
- "plt.legend()\n",
- "plt.grid()\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "In particular, the tasks are split into 2 parts, graph construction, and graph optimization. \n",
- "### Graph Construction\n",
- "\n",
- "Firstly the nodes are defined $\\boldsymbol{x} = \\boldsymbol{x}_{1:n}$ such that each node is the pose of the robot at time $t_i$\n",
- "Secondly, the edges i.e. the constraints, are constructed according to the following conditions:\n",
- "\n",
- "* robot moves from $\\boldsymbol{x}_i$ to $\\boldsymbol{x}_j$. This edge corresponds to the odometry measurement. Relative motion constraints (Not included in the previous minimal example).\n",
- "* Measurement constraints, this can be done in two ways:\n",
- " * The information matrix is set in such a way that it includes the landmarks in the map as well. Then the constraints can be entered in a straightforward fashion between a node $\\boldsymbol{x}_i$ and some landmark $m_k$\n",
- " * Through creating a virtual measurement among all the node that have observed the same landmark. More concretely, robot observes the same landmark from $\\boldsymbol{x}_i$ and $\\boldsymbol{x}_j$. Relative measurement constraint. The \"virtual measurement\" $\\boldsymbol{z}_{ij}$, which is the estimated pose of $\\boldsymbol{x}_j$ as seen from the node $\\boldsymbol{x}_i$. The virtual measurement can then be entered in the information matrix and vector in a similar fashion to the motion constraints.\n",
- "\n",
- "An edge is fully characterized by the values of the error (entry to information vector) and the local information matrix (entry to the system's information vector). The larger the local information matrix (lower $Q$ or $R$) the values that this edge will contribute with.\n",
- "\n",
- "Important Notes:\n",
- "\n",
- "* The addition to the information matrix and vector are added to the earlier values.\n",
- "* In the case of 2D robot, the constraints will be non-linear, therefore, a Jacobian of the error w.r.t the states is needed when updated $H$ and $b$.\n",
- "* The anchoring constraint is needed in order to avoid having a singular information matri.\n",
- "\n",
- "\n",
- "### Graph Optimization\n",
- "\n",
- "The result from this formulation yields an overdetermined system of equations.\n",
- "The goal after constructing the graph is to find: $x^* = \\underset{x}{\\mathrm{argmin}} ~ \\underset{ij} \\Sigma ~ f(e_{ij}) $, where $f$ is some error function that depends on the edges between to related nodes $i$ and $j$. The derivation in the references arrive at the solution for $x^* = H^{-1}b$ \n",
- "\n",
- "\n",
- "### Planar Example:\n",
- "\n",
- "Now we will go through an example with a more realistic case of a 2D robot with 3DoF, namely, $[x, y, \\theta]^T$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 3,
- "metadata": {},
- "outputs": [
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "# Simulation parameter\n",
- "Qsim = np.diag([0.01, np.deg2rad(0.010)])**2 # error added to range and bearing\n",
- "Rsim = np.diag([0.1, np.deg2rad(1.0)])**2 # error added to [v, w]\n",
- "\n",
- "DT = 2.0 # time tick [s]\n",
- "SIM_TIME = 100.0 # simulation time [s]\n",
- "MAX_RANGE = 30.0 # maximum observation range\n",
- "STATE_SIZE = 3 # State size [x,y,yaw]\n",
- "\n",
- "# TODO: Why not use Qsim ? \n",
- "# Covariance parameter of Graph Based SLAM\n",
- "C_SIGMA1 = 0.1\n",
- "C_SIGMA2 = 0.1\n",
- "C_SIGMA3 = np.deg2rad(1.0)\n",
- "\n",
- "MAX_ITR = 20 # Maximum iteration during optimization\n",
- "timesteps = 1\n",
- "\n",
- "# consider only 2 landmarks for simplicity\n",
- "# RFID positions [x, y, yaw]\n",
- "RFID = np.array([[10.0, -2.0, 0.0],\n",
- "# [15.0, 10.0, 0.0],\n",
- "# [3.0, 15.0, 0.0],\n",
- "# [-5.0, 20.0, 0.0],\n",
- "# [-5.0, 5.0, 0.0]\n",
- " ])\n",
- "\n",
- "# State Vector [x y yaw v]'\n",
- "xTrue = np.zeros((STATE_SIZE, 1))\n",
- "xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning\n",
- "xTrue[2] = np.deg2rad(45)\n",
- "xDR[2] = np.deg2rad(45)\n",
- "# history initial values\n",
- "hxTrue = xTrue\n",
- "hxDR = xTrue\n",
- "_, z, _, _ = observation(xTrue, xDR, np.array([[0,0]]).T, RFID)\n",
- "hz = [z]\n",
- "\n",
- "for i in range(timesteps):\n",
- " u = calc_input()\n",
- " xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)\n",
- " hxDR = np.hstack((hxDR, xDR))\n",
- " hxTrue = np.hstack((hxTrue, xTrue))\n",
- " hz.append(z)\n",
- "\n",
- "# visualize\n",
- "graphics_radius = 0.3\n",
- "plt.plot(RFID[:, 0], RFID[:, 1], \"*k\", markersize=20)\n",
- "plt.plot(hxDR[0, :], hxDR[1, :], '.', markersize=50, alpha=0.8, label='Odom')\n",
- "plt.plot(hxTrue[0, :], hxTrue[1, :], '.', markersize=20, alpha=0.6, label='X_true')\n",
- "\n",
- "for i in range(hxDR.shape[1]):\n",
- " x = hxDR[0, i]\n",
- " y = hxDR[1, i]\n",
- " yaw = hxDR[2, i]\n",
- " plt.plot([x, x + graphics_radius * np.cos(yaw)],\n",
- " [y, y + graphics_radius * np.sin(yaw)], 'r')\n",
- " d = hz[i][:, 0]\n",
- " angle = hz[i][:, 1]\n",
- " plt.plot([x + d * np.cos(angle + yaw)], [y + d * np.sin(angle + yaw)], '.',\n",
- " markersize=20, alpha=0.7)\n",
- " plt.legend()\n",
- "plt.grid() \n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 4,
- "metadata": {},
- "outputs": [],
- "source": [
- "# Copy the data to have a consistent naming with the .py file\n",
- "zlist = copy.deepcopy(hz)\n",
- "x_opt = copy.deepcopy(hxDR)\n",
- "xlist = copy.deepcopy(hxDR)\n",
- "number_of_nodes = x_opt.shape[1]\n",
- "n = number_of_nodes * STATE_SIZE"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "After the data has been saved, the graph will be constructed by looking at each pair for nodes. The virtual measurement is only created if two nodes have observed the same landmark at different points in time. The next cells are a walk through for a single iteration of graph construction -> optimization -> estimate update. "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 5,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "Node combinations: \n",
- " [(0, 1)]\n",
- "Node 0 observed landmark with ID 0.0\n",
- "Node 1 observed landmark with ID 0.0\n"
- ]
- }
- ],
- "source": [
- "# get all the possible combination of the different node\n",
- "zids = list(itertools.combinations(range(len(zlist)), 2))\n",
- "print(\"Node combinations: \\n\", zids)\n",
- "\n",
- "for i in range(xlist.shape[1]):\n",
- " print(\"Node {} observed landmark with ID {}\".format(i, zlist[i][0, 3]))"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "In the following code snippet the error based on the virtual measurement between node 0 and 1 will be created.\n",
- "The equations for the error is as follows: \n",
- "$e_{ij}^x = x_j + d_j cos(\\psi_j + \\theta_j) - x_i - d_i cos(\\psi_i + \\theta_i) $\n",
- "\n",
- "$e_{ij}^y = y_j + d_j sin(\\psi_j + \\theta_j) - y_i - d_i sin(\\psi_i + \\theta_i) $\n",
- "\n",
- "$e_{ij}^x = \\psi_j + \\theta_j - \\psi_i - \\theta_i $\n",
- "\n",
- "Where $[x_i, y_i, \\psi_i]$ is the pose for node $i$ and similarly for node $j$, $d$ is the measured distance at nodes $i$ and $j$, and $\\theta$ is the measured bearing to the landmark. The difference is visualized with the figure in the next cell.\n",
- "\n",
- "In case of perfect motion and perfect measurement the error shall be zero since $ x_j + d_j cos(\\psi_j + \\theta_j)$ should equal $x_i + d_i cos(\\psi_i + \\theta_i)$"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 6,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "0.0 1.427649841628278 -2.0126109674819155 -3.524048014922737\n",
- "For nodes (0, 1)\n",
- "Added edge with errors: \n",
- " [[-0.02 ]\n",
- " [-0.084]\n",
- " [ 0. ]]\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "# Initialize edges list\n",
- "edges = []\n",
- "\n",
- "# Go through all the different combinations\n",
- "for (t1, t2) in zids:\n",
- " x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1]\n",
- " x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2]\n",
- " \n",
- " # All nodes have valid observation with ID=0, therefore, no data association condition\n",
- " iz1 = 0\n",
- " iz2 = 0\n",
- " \n",
- " d1 = zlist[t1][iz1, 0]\n",
- " angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2]\n",
- " d2 = zlist[t2][iz2, 0]\n",
- " angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2]\n",
- " \n",
- " # find angle between observation and horizontal \n",
- " tangle1 = pi_2_pi(yaw1 + angle1)\n",
- " tangle2 = pi_2_pi(yaw2 + angle2)\n",
- " \n",
- " # project the observations \n",
- " tmp1 = d1 * math.cos(tangle1)\n",
- " tmp2 = d2 * math.cos(tangle2)\n",
- " tmp3 = d1 * math.sin(tangle1)\n",
- " tmp4 = d2 * math.sin(tangle2)\n",
- " \n",
- " edge = Edge()\n",
- " print(y1,y2, tmp3, tmp4)\n",
- " # calculate the error of the virtual measurement\n",
- " # node 1 as seen from node 2 throught the observations 1,2\n",
- " edge.e[0, 0] = x2 - x1 - tmp1 + tmp2\n",
- " edge.e[1, 0] = y2 - y1 - tmp3 + tmp4\n",
- " edge.e[2, 0] = pi_2_pi(yaw2 - yaw1 - tangle1 + tangle2)\n",
- "\n",
- " edge.d1, edge.d2 = d1, d2\n",
- " edge.yaw1, edge.yaw2 = yaw1, yaw2\n",
- " edge.angle1, edge.angle2 = angle1, angle2\n",
- " edge.id1, edge.id2 = t1, t2\n",
- " \n",
- " edges.append(edge)\n",
- " \n",
- " print(\"For nodes\",(t1,t2))\n",
- " print(\"Added edge with errors: \\n\", edge.e)\n",
- " \n",
- " # Visualize measurement projections\n",
- " plt.plot(RFID[0, 0], RFID[0, 1], \"*k\", markersize=20)\n",
- " plt.plot([x1,x2],[y1,y2], '.', markersize=50, alpha=0.8)\n",
- " plt.plot([x1, x1 + graphics_radius * np.cos(yaw1)],\n",
- " [y1, y1 + graphics_radius * np.sin(yaw1)], 'r')\n",
- " plt.plot([x2, x2 + graphics_radius * np.cos(yaw2)],\n",
- " [y2, y2 + graphics_radius * np.sin(yaw2)], 'r')\n",
- " \n",
- " plt.plot([x1,x1+tmp1], [y1,y1], label=\"obs 1 x\")\n",
- " plt.plot([x2,x2+tmp2], [y2,y2], label=\"obs 2 x\")\n",
- " plt.plot([x1,x1], [y1,y1+tmp3], label=\"obs 1 y\")\n",
- " plt.plot([x2,x2], [y2,y2+tmp4], label=\"obs 2 y\")\n",
- " plt.plot(x1+tmp1, y1+tmp3, 'o')\n",
- " plt.plot(x2+tmp2, y2+tmp4, 'o')\n",
- "plt.legend()\n",
- "plt.grid()\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "Since the constraints equations derived before are non-linear, linearization is needed before we can insert them into the information matrix and information vector. Two jacobians \n",
- "\n",
- "$A = \\frac{\\partial e_{ij}}{\\partial \\boldsymbol{x}_i}$ as $\\boldsymbol{x}_i$ holds the three variabls x, y, and theta.\n",
- "Similarly, \n",
- "$B = \\frac{\\partial e_{ij}}{\\partial \\boldsymbol{x}_j}$ "
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 7,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "The determinant of H: 0.0\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- },
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "The determinant of H after origin constraint: 716.1972439134918\n"
- ]
- },
- {
- "data": {
- "image/png": "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\n",
- "text/plain": [
- ""
- ]
- },
- "metadata": {
- "needs_background": "light"
- },
- "output_type": "display_data"
- }
- ],
- "source": [
- "# Initialize the system information matrix and information vector\n",
- "H = np.zeros((n, n))\n",
- "b = np.zeros((n, 1))\n",
- "x_opt = copy.deepcopy(hxDR)\n",
- "\n",
- "for edge in edges:\n",
- " id1 = edge.id1 * STATE_SIZE\n",
- " id2 = edge.id2 * STATE_SIZE\n",
- " \n",
- " t1 = edge.yaw1 + edge.angle1\n",
- " A = np.array([[-1.0, 0, edge.d1 * math.sin(t1)],\n",
- " [0, -1.0, -edge.d1 * math.cos(t1)],\n",
- " [0, 0, -1.0]])\n",
- "\n",
- " t2 = edge.yaw2 + edge.angle2\n",
- " B = np.array([[1.0, 0, -edge.d2 * math.sin(t2)],\n",
- " [0, 1.0, edge.d2 * math.cos(t2)],\n",
- " [0, 0, 1.0]])\n",
- " \n",
- " # TODO: use Qsim instead of sigma\n",
- " sigma = np.diag([C_SIGMA1, C_SIGMA2, C_SIGMA3])\n",
- " Rt1 = calc_rotational_matrix(tangle1)\n",
- " Rt2 = calc_rotational_matrix(tangle2)\n",
- " edge.omega = np.linalg.inv(Rt1 @ sigma @ Rt1.T + Rt2 @ sigma @ Rt2.T)\n",
- "\n",
- " # Fill in entries in H and b\n",
- " H[id1:id1 + STATE_SIZE, id1:id1 + STATE_SIZE] += A.T @ edge.omega @ A\n",
- " H[id1:id1 + STATE_SIZE, id2:id2 + STATE_SIZE] += A.T @ edge.omega @ B\n",
- " H[id2:id2 + STATE_SIZE, id1:id1 + STATE_SIZE] += B.T @ edge.omega @ A\n",
- " H[id2:id2 + STATE_SIZE, id2:id2 + STATE_SIZE] += B.T @ edge.omega @ B\n",
- "\n",
- " b[id1:id1 + STATE_SIZE] += (A.T @ edge.omega @ edge.e)\n",
- " b[id2:id2 + STATE_SIZE] += (B.T @ edge.omega @ edge.e)\n",
- " \n",
- "\n",
- "print(\"The determinant of H: \", np.linalg.det(H))\n",
- "plt.figure()\n",
- "plt.subplot(1,2,1)\n",
- "plt.imshow(H, extent=[0, n, 0, n])\n",
- "plt.subplot(1,2,2)\n",
- "plt.imshow(b, extent=[0, 1, 0, n])\n",
- "plt.show() \n",
- "\n",
- "# Fix the origin, multiply by large number gives same results but better visualization\n",
- "H[0:STATE_SIZE, 0:STATE_SIZE] += np.identity(STATE_SIZE)\n",
- "print(\"The determinant of H after origin constraint: \", np.linalg.det(H)) \n",
- "plt.figure()\n",
- "plt.subplot(1,2,1)\n",
- "plt.imshow(H, extent=[0, n, 0, n])\n",
- "plt.subplot(1,2,2)\n",
- "plt.imshow(b, extent=[0, 1, 0, n])\n",
- "plt.show()"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 8,
- "metadata": {},
- "outputs": [
- {
- "name": "stdout",
- "output_type": "stream",
- "text": [
- "dx: \n",
- " [[ 0. ]\n",
- " [-0. ]\n",
- " [ 0. ]\n",
- " [ 0.02 ]\n",
- " [ 0.084]\n",
- " [-0. ]]\n",
- "ground truth: \n",
- " [[0. 1.414]\n",
- " [0. 1.414]\n",
- " [0.785 0.985]]\n",
- "Odom: \n",
- " [[0. 1.428]\n",
- " [0. 1.428]\n",
- " [0.785 0.976]]\n",
- "SLAM: \n",
- " [[ 0. 1.448]\n",
- " [-0. 1.512]\n",
- " [ 0.785 0.976]]\n",
- "\n",
- "graphSLAM localization error: 0.0107290727510571\n",
- "Odom localization error: 0.0004460978857535104\n"
- ]
- }
- ],
- "source": [
- "# Find the solution (first iteration)\n",
- "dx = - np.linalg.inv(H) @ b\n",
- "for i in range(number_of_nodes):\n",
- " x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0]\n",
- "print(\"dx: \\n\",dx)\n",
- "print(\"ground truth: \\n \",hxTrue)\n",
- "print(\"Odom: \\n\", hxDR)\n",
- "print(\"SLAM: \\n\", x_opt)\n",
- "\n",
- "# performance will improve with more iterations, nodes and landmarks.\n",
- "print(\"\\ngraphSLAM localization error: \", np.sum((x_opt - hxTrue) ** 2))\n",
- "print(\"Odom localization error: \", np.sum((hxDR - hxTrue) ** 2))"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### The references:\n",
- "\n",
- "\n",
- "* http://robots.stanford.edu/papers/thrun.graphslam.pdf\n",
- "\n",
- "* http://ais.informatik.uni-freiburg.de/teaching/ss13/robotics/slides/16-graph-slam.pdf\n",
- "\n",
- "* http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf\n",
- "\n",
- "N.B.\n",
- "An additional step is required that uses the estimated path to update the belief regarding the map."
- ]
- },
- {
- "cell_type": "code",
- "execution_count": null,
- "metadata": {},
- "outputs": [],
- "source": []
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.5"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py
index b40ad6494e..edd20a959c 100644
--- a/SLAM/GraphBasedSLAM/graph_based_slam.py
+++ b/SLAM/GraphBasedSLAM/graph_based_slam.py
@@ -6,20 +6,26 @@
Ref
-[A Tutorial on Graph-Based SLAM](http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf)
+[A Tutorial on Graph-Based SLAM]
+(http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf)
"""
+import sys
+import pathlib
+sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
-import numpy as np
-import math
import copy
import itertools
-import matplotlib.pyplot as plt
+import math
+import matplotlib.pyplot as plt
+import numpy as np
+from scipy.spatial.transform import Rotation as Rot
+from utils.angle import angle_mod
# Simulation parameter
-Qsim = np.diag([0.2, np.deg2rad(1.0)])**2
-Rsim = np.diag([0.1, np.deg2rad(10.0)])**2
+Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2
+R_sim = np.diag([0.1, np.deg2rad(10.0)]) ** 2
DT = 2.0 # time tick [s]
SIM_TIME = 100.0 # simulation time [s]
@@ -33,11 +39,11 @@
MAX_ITR = 20 # Maximum iteration
-show_graph_dtime = 20.0 # [s]
+show_graph_d_time = 20.0 # [s]
show_animation = True
-class Edge():
+class Edge:
def __init__(self):
self.e = np.zeros((3, 1))
@@ -52,26 +58,21 @@ def __init__(self):
self.id2 = 0
-def cal_observation_sigma(d):
-
+def cal_observation_sigma():
sigma = np.zeros((3, 3))
- sigma[0, 0] = C_SIGMA1**2
- sigma[1, 1] = C_SIGMA2**2
- sigma[2, 2] = C_SIGMA3**2
+ sigma[0, 0] = C_SIGMA1 ** 2
+ sigma[1, 1] = C_SIGMA2 ** 2
+ sigma[2, 2] = C_SIGMA3 ** 2
return sigma
-def calc_rotational_matrix(angle):
-
- Rt = np.array([[math.cos(angle), -math.sin(angle), 0],
- [math.sin(angle), math.cos(angle), 0],
- [0, 0, 1.0]])
- return Rt
+def calc_3d_rotational_matrix(angle):
+ return Rot.from_euler('z', angle).as_matrix()
def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1,
- angle1, phi1, d2, angle2, phi2, t1, t2):
+ angle1, d2, angle2, t1, t2):
edge = Edge()
tangle1 = pi_2_pi(yaw1 + angle1)
@@ -85,11 +86,11 @@ def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1,
edge.e[1, 0] = y2 - y1 - tmp3 + tmp4
edge.e[2, 0] = 0
- Rt1 = calc_rotational_matrix(tangle1)
- Rt2 = calc_rotational_matrix(tangle2)
+ Rt1 = calc_3d_rotational_matrix(tangle1)
+ Rt2 = calc_3d_rotational_matrix(tangle2)
- sig1 = cal_observation_sigma(d1)
- sig2 = cal_observation_sigma(d2)
+ sig1 = cal_observation_sigma()
+ sig2 = cal_observation_sigma()
edge.omega = np.linalg.inv(Rt1 @ sig1 @ Rt1.T + Rt2 @ sig2 @ Rt2.T)
@@ -101,34 +102,33 @@ def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1,
return edge
-def calc_edges(xlist, zlist):
-
+def calc_edges(x_list, z_list):
edges = []
cost = 0.0
- zids = list(itertools.combinations(range(len(zlist)), 2))
+ z_ids = list(itertools.combinations(range(len(z_list)), 2))
- for (t1, t2) in zids:
- x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1]
- x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2]
+ for (t1, t2) in z_ids:
+ x1, y1, yaw1 = x_list[0, t1], x_list[1, t1], x_list[2, t1]
+ x2, y2, yaw2 = x_list[0, t2], x_list[1, t2], x_list[2, t2]
- if zlist[t1] is None or zlist[t2] is None:
+ if z_list[t1] is None or z_list[t2] is None:
continue # No observation
- for iz1 in range(len(zlist[t1][:, 0])):
- for iz2 in range(len(zlist[t2][:, 0])):
- if zlist[t1][iz1, 3] == zlist[t2][iz2, 3]:
- d1 = zlist[t1][iz1, 0]
- angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2]
- d2 = zlist[t2][iz2, 0]
- angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2]
+ for iz1 in range(len(z_list[t1][:, 0])):
+ for iz2 in range(len(z_list[t2][:, 0])):
+ if z_list[t1][iz1, 3] == z_list[t2][iz2, 3]:
+ d1 = z_list[t1][iz1, 0]
+ angle1, _ = z_list[t1][iz1, 1], z_list[t1][iz1, 2]
+ d2 = z_list[t2][iz2, 0]
+ angle2, _ = z_list[t2][iz2, 1], z_list[t2][iz2, 2]
edge = calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1,
- angle1, phi1, d2, angle2, phi2, t1, t2)
+ angle1, d2, angle2, t1, t2)
edges.append(edge)
- cost += (edge.e.T @ (edge.omega) @ edge.e)[0, 0]
+ cost += (edge.e.T @ edge.omega @ edge.e)[0, 0]
- print("cost:", cost, ",nedge:", len(edges))
+ print("cost:", cost, ",n_edge:", len(edges))
return edges
@@ -147,7 +147,6 @@ def calc_jacobian(edge):
def fill_H_and_b(H, b, edge):
-
A, B = calc_jacobian(edge)
id1 = edge.id1 * STATE_SIZE
@@ -167,14 +166,14 @@ def fill_H_and_b(H, b, edge):
def graph_based_slam(x_init, hz):
print("start graph based slam")
- zlist = copy.deepcopy(hz)
+ z_list = copy.deepcopy(hz)
x_opt = copy.deepcopy(x_init)
nt = x_opt.shape[1]
n = nt * STATE_SIZE
for itr in range(MAX_ITR):
- edges = calc_edges(x_opt, zlist)
+ edges = calc_edges(x_opt, z_list)
H = np.zeros((n, n))
b = np.zeros((n, 1))
@@ -190,7 +189,7 @@ def graph_based_slam(x_init, hz):
for i in range(nt):
x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0]
- diff = dx.T @ dx
+ diff = (dx.T @ dx)[0, 0]
print("iteration: %d, diff: %f" % (itr + 1, diff))
if diff < 1.0e-5:
break
@@ -200,13 +199,12 @@ def graph_based_slam(x_init, hz):
def calc_input():
v = 1.0 # [m/s]
- yawrate = 0.1 # [rad/s]
- u = np.array([[v, yawrate]]).T
+ yaw_rate = 0.1 # [rad/s]
+ u = np.array([[v, yaw_rate]]).T
return u
def observation(xTrue, xd, u, RFID):
-
xTrue = motion_model(xTrue, u)
# add noise to gps x-y
@@ -216,20 +214,20 @@ def observation(xTrue, xd, u, RFID):
dx = RFID[i, 0] - xTrue[0, 0]
dy = RFID[i, 1] - xTrue[1, 0]
- d = math.sqrt(dx**2 + dy**2)
+ d = math.hypot(dx, dy)
angle = pi_2_pi(math.atan2(dy, dx)) - xTrue[2, 0]
phi = pi_2_pi(math.atan2(dy, dx))
if d <= MAX_RANGE:
- dn = d + np.random.randn() * Qsim[0, 0] # add noise
- angle_noise = np.random.randn() * Qsim[1, 1]
+ dn = d + np.random.randn() * Q_sim[0, 0] # add noise
+ angle_noise = np.random.randn() * Q_sim[1, 1]
angle += angle_noise
phi += angle_noise
zi = np.array([dn, angle, phi, i])
z = np.vstack((z, zi))
# add noise to input
- ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
- ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
+ ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0]
+ ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1]
ud = np.array([[ud1, ud2]]).T
xd = motion_model(xd, ud)
@@ -238,7 +236,6 @@ def observation(xTrue, xd, u, RFID):
def motion_model(x, u):
-
F = np.array([[1.0, 0, 0],
[0, 1.0, 0],
[0, 0, 1.0]])
@@ -253,7 +250,7 @@ def motion_model(x, u):
def pi_2_pi(angle):
- return (angle + math.pi) % (2 * math.pi) - math.pi
+ return angle_mod(angle)
def main():
@@ -277,7 +274,7 @@ def main():
hxTrue = []
hxDR = []
hz = []
- dtime = 0.0
+ d_time = 0.0
init = False
while SIM_TIME >= time:
@@ -290,20 +287,23 @@ def main():
hxTrue = np.hstack((hxTrue, xTrue))
time += DT
- dtime += DT
+ d_time += DT
u = calc_input()
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
hz.append(z)
- if dtime >= show_graph_dtime:
+ if d_time >= show_graph_d_time:
x_opt = graph_based_slam(hxDR, hz)
- dtime = 0.0
+ d_time = 0.0
if show_animation: # pragma: no cover
plt.cla()
-
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
plt.plot(hxTrue[0, :].flatten(),
@@ -319,4 +319,4 @@ def main():
if __name__ == '__main__':
- main()
\ No newline at end of file
+ main()
diff --git a/SLAM/GraphBasedSLAM/graphslam/__init__.py b/SLAM/GraphBasedSLAM/graphslam/__init__.py
new file mode 100644
index 0000000000..6aa2872e77
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/__init__.py
@@ -0,0 +1,9 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+"""Graph SLAM solver in Python.
+
+"""
diff --git a/SLAM/GraphBasedSLAM/graphslam/edge/__init__.py b/SLAM/GraphBasedSLAM/graphslam/edge/__init__.py
new file mode 100644
index 0000000000..afb8549087
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/edge/__init__.py
@@ -0,0 +1,5 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
diff --git a/SLAM/GraphBasedSLAM/graphslam/edge/edge_odometry.py b/SLAM/GraphBasedSLAM/graphslam/edge/edge_odometry.py
new file mode 100644
index 0000000000..b247b97b43
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/edge/edge_odometry.py
@@ -0,0 +1,180 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+r"""A class for odometry edges.
+
+"""
+
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+
+#: The difference that will be used for numerical differentiation
+EPSILON = 1e-6
+
+
+class EdgeOdometry:
+ r"""A class for representing odometry edges in Graph SLAM.
+
+ Parameters
+ ----------
+ vertices : list[graphslam.vertex.Vertex]
+ A list of the vertices constrained by the edge
+ information : np.ndarray
+ The information matrix :math:`\Omega_j` associated with the edge
+ estimate : graphslam.pose.se2.PoseSE2
+ The expected measurement :math:`\mathbf{z}_j`
+
+ Attributes
+ ----------
+ vertices : list[graphslam.vertex.Vertex]
+ A list of the vertices constrained by the edge
+ information : np.ndarray
+ The information matrix :math:`\Omega_j` associated with the edge
+ estimate : PoseSE2
+ The expected measurement :math:`\mathbf{z}_j`
+
+ """
+ def __init__(self, vertex_ids, information, estimate, vertices=None):
+ self.vertex_ids = vertex_ids
+ self.information = information
+ self.estimate = estimate
+ self.vertices = vertices
+
+ def calc_error(self):
+ r"""Calculate the error for the edge: :math:`\mathbf{e}_j \in \mathbb{R}^\bullet`.
+
+ .. math::
+
+ \mathbf{e}_j = \mathbf{z}_j - (p_2 \ominus p_1)
+
+
+ Returns
+ -------
+ np.ndarray
+ The error for the edge
+
+ """
+ return (self.estimate - (self.vertices[1].pose - self.vertices[0].pose)).to_compact()
+
+ def calc_chi2(self):
+ r"""Calculate the :math:`\chi^2` error for the edge.
+
+ .. math::
+
+ \mathbf{e}_j^T \Omega_j \mathbf{e}_j
+
+
+ Returns
+ -------
+ float
+ The :math:`\chi^2` error for the edge
+
+ """
+ err = self.calc_error()
+
+ return np.dot(np.dot(np.transpose(err), self.information), err)
+
+ def calc_chi2_gradient_hessian(self):
+ r"""Calculate the edge's contributions to the graph's :math:`\chi^2` error, gradient (:math:`\mathbf{b}`), and Hessian (:math:`H`).
+
+ Returns
+ -------
+ float
+ The :math:`\chi^2` error for the edge
+ dict
+ The edge's contribution(s) to the gradient
+ dict
+ The edge's contribution(s) to the Hessian
+
+ """
+ chi2 = self.calc_chi2()
+
+ err = self.calc_error()
+
+ jacobians = self.calc_jacobians()
+
+ return chi2, {v.index: np.dot(np.dot(np.transpose(err), self.information), jacobian) for v, jacobian in zip(self.vertices, jacobians)}, {(self.vertices[i].index, self.vertices[j].index): np.dot(np.dot(np.transpose(jacobians[i]), self.information), jacobians[j]) for i in range(len(jacobians)) for j in range(i, len(jacobians))}
+
+ def calc_jacobians(self):
+ r"""Calculate the Jacobian of the edge's error with respect to each constrained pose.
+
+ .. math::
+
+ \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right]
+
+
+ Returns
+ -------
+ list[np.ndarray]
+ The Jacobian matrices for the edge with respect to each constrained pose
+
+ """
+ err = self.calc_error()
+
+ # The dimensionality of the compact pose representation
+ dim = len(self.vertices[0].pose.to_compact())
+
+ return [self._calc_jacobian(err, dim, i) for i in range(len(self.vertices))]
+
+ def _calc_jacobian(self, err, dim, vertex_index):
+ r"""Calculate the Jacobian of the edge with respect to the specified vertex's pose.
+
+ Parameters
+ ----------
+ err : np.ndarray
+ The current error for the edge (see :meth:`EdgeOdometry.calc_error`)
+ dim : int
+ The dimensionality of the compact pose representation
+ vertex_index : int
+ The index of the vertex (pose) for which we are computing the Jacobian
+
+ Returns
+ -------
+ np.ndarray
+ The Jacobian of the edge with respect to the specified vertex's pose
+
+ """
+ jacobian = np.zeros(err.shape + (dim,))
+ p0 = self.vertices[vertex_index].pose.copy()
+
+ for d in range(dim):
+ # update the pose
+ delta_pose = np.zeros(dim)
+ delta_pose[d] = EPSILON
+ self.vertices[vertex_index].pose += delta_pose
+
+ # compute the numerical derivative
+ jacobian[:, d] = (self.calc_error() - err) / EPSILON
+
+ # restore the pose
+ self.vertices[vertex_index].pose = p0.copy()
+
+ return jacobian
+
+ def to_g2o(self):
+ """Export the edge to the .g2o format.
+
+ Returns
+ -------
+ str
+ The edge in .g2o format
+
+ """
+ return "EDGE_SE2 {} {} {} {} {} ".format(self.vertex_ids[0], self.vertex_ids[1], self.estimate[0], self.estimate[1], self.estimate[2]) + " ".join([str(x) for x in self.information[np.triu_indices(3, 0)]]) + "\n"
+
+ def plot(self, color='b'):
+ """Plot the edge.
+
+ Parameters
+ ----------
+ color : str
+ The color that will be used to plot the edge
+
+ """
+ xy = np.array([v.pose.position for v in self.vertices])
+ plt.plot(xy[:, 0], xy[:, 1], color=color)
diff --git a/SLAM/GraphBasedSLAM/graphslam/graph.py b/SLAM/GraphBasedSLAM/graphslam/graph.py
new file mode 100644
index 0000000000..672f63d60e
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/graph.py
@@ -0,0 +1,282 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+r"""A ``Graph`` class that stores the edges and vertices required for Graph SLAM.
+
+"""
+
+import warnings
+from collections import defaultdict
+from functools import reduce
+
+import matplotlib.pyplot as plt
+import numpy as np
+from scipy.sparse import SparseEfficiencyWarning, lil_matrix
+from scipy.sparse.linalg import spsolve
+
+warnings.simplefilter("ignore", SparseEfficiencyWarning)
+warnings.filterwarnings("ignore", category=SparseEfficiencyWarning)
+
+
+# pylint: disable=too-few-public-methods
+class _Chi2GradientHessian:
+ r"""A class that is used to aggregate the :math:`\chi^2` error, gradient, and Hessian.
+
+ Parameters
+ ----------
+ dim : int
+ The compact dimensionality of the poses
+
+ Attributes
+ ----------
+ chi2 : float
+ The :math:`\chi^2` error
+ dim : int
+ The compact dimensionality of the poses
+ gradient : defaultdict
+ The contributions to the gradient vector
+ hessian : defaultdict
+ The contributions to the Hessian matrix
+
+ """
+
+ def __init__(self, dim):
+ self.chi2 = 0.
+ self.dim = dim
+ self.gradient = defaultdict(lambda: np.zeros(dim))
+ self.hessian = defaultdict(lambda: np.zeros((dim, dim)))
+
+ @staticmethod
+ def update(chi2_grad_hess, incoming):
+ r"""Update the :math:`\chi^2` error and the gradient and Hessian dictionaries.
+
+ Parameters
+ ----------
+ chi2_grad_hess : _Chi2GradientHessian
+ The ``_Chi2GradientHessian`` that will be updated
+ incoming : tuple
+
+ """
+ chi2_grad_hess.chi2 += incoming[0]
+
+ for idx, contrib in incoming[1].items():
+ chi2_grad_hess.gradient[idx] += contrib
+
+ for (idx1, idx2), contrib in incoming[2].items():
+ if idx1 <= idx2:
+ chi2_grad_hess.hessian[idx1, idx2] += contrib
+ else:
+ chi2_grad_hess.hessian[idx2, idx1] += np.transpose(contrib)
+
+ return chi2_grad_hess
+
+
+class Graph(object):
+ r"""A graph that will be optimized via Graph SLAM.
+
+ Parameters
+ ----------
+ edges : list[graphslam.edge.edge_odometry.EdgeOdometry]
+ A list of the vertices in the graph
+ vertices : list[graphslam.vertex.Vertex]
+ A list of the vertices in the graph
+
+ Attributes
+ ----------
+ _chi2 : float, None
+ The current :math:`\chi^2` error, or ``None`` if it has not yet been computed
+ _edges : list[graphslam.edge.edge_odometry.EdgeOdometry]
+ A list of the edges (i.e., constraints) in the graph
+ _gradient : numpy.ndarray, None
+ The gradient :math:`\mathbf{b}` of the :math:`\chi^2` error, or ``None`` if it has not yet been computed
+ _hessian : scipy.sparse.lil_matrix, None
+ The Hessian matrix :math:`H`, or ``None`` if it has not yet been computed
+ _vertices : list[graphslam.vertex.Vertex]
+ A list of the vertices in the graph
+
+ """
+
+ def __init__(self, edges, vertices):
+ # The vertices and edges lists
+ self._edges = edges
+ self._vertices = vertices
+
+ # The chi^2 error, gradient, and Hessian
+ self._chi2 = None
+ self._gradient = None
+ self._hessian = None
+
+ self._link_edges()
+
+ def _link_edges(self):
+ """Fill in the ``vertices`` attributes for the graph's edges.
+
+ """
+ index_id_dict = {i: v.id for i, v in enumerate(self._vertices)}
+ id_index_dict = {v_id: v_index for v_index, v_id in
+ index_id_dict.items()}
+
+ # Fill in the vertices' `index` attribute
+ for v in self._vertices:
+ v.index = id_index_dict[v.id]
+
+ for e in self._edges:
+ e.vertices = [self._vertices[id_index_dict[v_id]] for v_id in
+ e.vertex_ids]
+
+ def calc_chi2(self):
+ r"""Calculate the :math:`\chi^2` error for the ``Graph``.
+
+ Returns
+ -------
+ float
+ The :math:`\chi^2` error
+
+ """
+ self._chi2 = sum((e.calc_chi2() for e in self._edges))
+ return self._chi2
+
+ def _calc_chi2_gradient_hessian(self):
+ r"""Calculate the :math:`\chi^2` error, the gradient :math:`\mathbf{b}`, and the Hessian :math:`H`.
+
+ """
+ n = len(self._vertices)
+ dim = len(self._vertices[0].pose.to_compact())
+ chi2_gradient_hessian = reduce(_Chi2GradientHessian.update,
+ (e.calc_chi2_gradient_hessian()
+ for e in self._edges),
+ _Chi2GradientHessian(dim))
+
+ self._chi2 = chi2_gradient_hessian.chi2
+
+ # Fill in the gradient vector
+ self._gradient = np.zeros(n * dim, dtype=float)
+ for idx, cont in chi2_gradient_hessian.gradient.items():
+ self._gradient[idx * dim: (idx + 1) * dim] += cont
+
+ # Fill in the Hessian matrix
+ self._hessian = lil_matrix((n * dim, n * dim), dtype=float)
+ for (row_idx, col_idx), cont in chi2_gradient_hessian.hessian.items():
+ x_start = row_idx * dim
+ x_end = (row_idx + 1) * dim
+ y_start = col_idx * dim
+ y_end = (col_idx + 1) * dim
+ self._hessian[x_start:x_end, y_start:y_end] = cont
+
+ if row_idx != col_idx:
+ x_start = col_idx * dim
+ x_end = (col_idx + 1) * dim
+ y_start = row_idx * dim
+ y_end = (row_idx + 1) * dim
+ self._hessian[x_start:x_end, y_start:y_end] = \
+ np.transpose(cont)
+
+ def optimize(self, tol=1e-4, max_iter=20, fix_first_pose=True):
+ r"""Optimize the :math:`\chi^2` error for the ``Graph``.
+
+ Parameters
+ ----------
+ tol : float
+ If the relative decrease in the :math:`\chi^2` error between iterations is less than ``tol``, we will stop
+ max_iter : int
+ The maximum number of iterations
+ fix_first_pose : bool
+ If ``True``, we will fix the first pose
+
+ """
+ n = len(self._vertices)
+ dim = len(self._vertices[0].pose.to_compact())
+
+ # Previous iteration's chi^2 error
+ chi2_prev = -1.
+
+ # For displaying the optimization progress
+ print("\nIteration chi^2 rel. change")
+ print("--------- ----- -----------")
+
+ for i in range(max_iter):
+ self._calc_chi2_gradient_hessian()
+
+ # Check for convergence (from the previous iteration); this avoids having to calculate chi^2 twice
+ if i > 0:
+ rel_diff = (chi2_prev - self._chi2) / (
+ chi2_prev + np.finfo(float).eps)
+ print(
+ "{:9d} {:20.4f} {:18.6f}".format(i, self._chi2, -rel_diff))
+ if self._chi2 < chi2_prev and rel_diff < tol:
+ return
+ else:
+ print("{:9d} {:20.4f}".format(i, self._chi2))
+
+ # Update the previous iteration's chi^2 error
+ chi2_prev = self._chi2
+
+ # Hold the first pose fixed
+ if fix_first_pose:
+ self._hessian[:dim, :] = 0.
+ self._hessian[:, :dim] = 0.
+ self._hessian[:dim, :dim] += np.eye(dim)
+ self._gradient[:dim] = 0.
+
+ # Solve for the updates
+ dx = spsolve(self._hessian, -self._gradient)
+
+ # Apply the updates
+ for v, dx_i in zip(self._vertices, np.split(dx, n)):
+ v.pose += dx_i
+
+ # If we reached the maximum number of iterations, print out the final iteration's results
+ self.calc_chi2()
+ rel_diff = (chi2_prev - self._chi2) / (chi2_prev + np.finfo(float).eps)
+ print("{:9d} {:20.4f} {:18.6f}".format(
+ max_iter, self._chi2, -rel_diff))
+
+ def to_g2o(self, outfile):
+ """Save the graph in .g2o format.
+
+ Parameters
+ ----------
+ outfile : str
+ The path where the graph will be saved
+
+ """
+ with open(outfile, 'w') as f:
+ for v in self._vertices:
+ f.write(v.to_g2o())
+
+ for e in self._edges:
+ f.write(e.to_g2o())
+
+ def plot(self, vertex_color='r', vertex_marker='o', vertex_markersize=3,
+ edge_color='b', title=None):
+ """Plot the graph.
+
+ Parameters
+ ----------
+ vertex_color : str
+ The color that will be used to plot the vertices
+ vertex_marker : str
+ The marker that will be used to plot the vertices
+ vertex_markersize : int
+ The size of the plotted vertices
+ edge_color : str
+ The color that will be used to plot the edges
+ title : str, None
+ The title that will be used for the plot
+
+ """
+ plt.figure()
+
+ for e in self._edges:
+ e.plot(edge_color)
+
+ for v in self._vertices:
+ v.plot(vertex_color, vertex_marker, vertex_markersize)
+
+ if title:
+ plt.title(title)
+
+ plt.show()
diff --git a/SLAM/GraphBasedSLAM/graphslam/load.py b/SLAM/GraphBasedSLAM/graphslam/load.py
new file mode 100644
index 0000000000..ebf4291456
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/load.py
@@ -0,0 +1,66 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+"""Functions for loading graphs.
+
+"""
+
+import logging
+
+import numpy as np
+
+from .edge.edge_odometry import EdgeOdometry
+from .graph import Graph
+from .pose.se2 import PoseSE2
+from .util import upper_triangular_matrix_to_full_matrix
+from .vertex import Vertex
+
+_LOGGER = logging.getLogger(__name__)
+
+
+def load_g2o_se2(infile):
+ """Load an :math:`SE(2)` graph from a .g2o file.
+
+ Parameters
+ ----------
+ infile : str
+ The path to the .g2o file
+
+ Returns
+ -------
+ Graph
+ The loaded graph
+
+ """
+ edges = []
+ vertices = []
+
+ with open(infile) as f:
+ for line in f.readlines():
+ if line.startswith("VERTEX_SE2"):
+ numbers = line[10:].split()
+ arr = np.array([float(number) for number in numbers[1:]],
+ dtype=float)
+ p = PoseSE2(arr[:2], arr[2])
+ v = Vertex(int(numbers[0]), p)
+ vertices.append(v)
+ continue
+
+ if line.startswith("EDGE_SE2"):
+ numbers = line[9:].split()
+ arr = np.array([float(number) for number in numbers[2:]],
+ dtype=float)
+ vertex_ids = [int(numbers[0]), int(numbers[1])]
+ estimate = PoseSE2(arr[:2], arr[2])
+ information = upper_triangular_matrix_to_full_matrix(arr[3:], 3)
+ e = EdgeOdometry(vertex_ids, information, estimate)
+ edges.append(e)
+ continue
+
+ if line.strip():
+ _LOGGER.warning("Line not supported -- '%s'", line.rstrip())
+
+ return Graph(edges, vertices)
diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py
new file mode 100644
index 0000000000..afb8549087
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py
@@ -0,0 +1,5 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/se2.py b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py
new file mode 100644
index 0000000000..2a32e765f7
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py
@@ -0,0 +1,184 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+r"""Representation of a pose in :math:`SE(2)`.
+
+"""
+
+import math
+import numpy as np
+
+from ..util import neg_pi_to_pi
+
+
+class PoseSE2(np.ndarray):
+ r"""A representation of a pose in :math:`SE(2)`.
+
+ Parameters
+ ----------
+ position : np.ndarray, list
+ The position in :math:`\mathbb{R}^2`
+ orientation : float
+ The angle of the pose (in radians)
+
+ """
+
+ def __new__(cls, position, orientation):
+ obj = np.array([position[0], position[1], neg_pi_to_pi(orientation)],
+ dtype=float).view(cls)
+ return obj
+
+ # pylint: disable=arguments-differ
+ def copy(self):
+ """Return a copy of the pose.
+
+ Returns
+ -------
+ PoseSE2
+ A copy of the pose
+
+ """
+ return PoseSE2(self[:2], self[2])
+
+ def to_array(self):
+ """Return the pose as a numpy array.
+
+ Returns
+ -------
+ np.ndarray
+ The pose as a numpy array
+
+ """
+ return np.array(self)
+
+ def to_compact(self):
+ """Return the pose as a compact numpy array.
+
+ Returns
+ -------
+ np.ndarray
+ The pose as a compact numpy array
+
+ """
+ return np.array(self)
+
+ def to_matrix(self):
+ """Return the pose as an :math:`SE(2)` matrix.
+
+ Returns
+ -------
+ np.ndarray
+ The pose as an :math:`SE(2)` matrix
+
+ """
+ return np.array([[np.cos(self[2]), -np.sin(self[2]), self[0]],
+ [np.sin(self[2]), np.cos(self[2]), self[1]],
+ [0., 0., 1.]], dtype=float)
+
+ @classmethod
+ def from_matrix(cls, matrix):
+ """Return the pose as an :math:`SE(2)` matrix.
+
+ Parameters
+ ----------
+ matrix : np.ndarray
+ The :math:`SE(2)` matrix that will be converted to a `PoseSE2` instance
+
+ Returns
+ -------
+ PoseSE2
+ The matrix as a `PoseSE2` object
+
+ """
+ return cls([matrix[0, 2], matrix[1, 2]],
+ math.atan2(matrix[1, 0], matrix[0, 0]))
+
+ # ======================================================================= #
+ # #
+ # Properties #
+ # #
+ # ======================================================================= #
+ @property
+ def position(self):
+ """Return the pose's position.
+
+ Returns
+ -------
+ np.ndarray
+ The position portion of the pose
+
+ """
+ return np.array(self[:2])
+
+ @property
+ def orientation(self):
+ """Return the pose's orientation.
+
+ Returns
+ -------
+ float
+ The angle of the pose
+
+ """
+ return self[2]
+
+ @property
+ def inverse(self):
+ """Return the pose's inverse.
+
+ Returns
+ -------
+ PoseSE2
+ The pose's inverse
+
+ """
+ return PoseSE2([-self[0] * np.cos(self[2]) - self[1] * np.sin(self[2]),
+ self[0] * np.sin(self[2]) - self[1] * np.cos(self[2])],
+ -self[2])
+
+ # ======================================================================= #
+ # #
+ # Magic Methods #
+ # #
+ # ======================================================================= #
+ def __add__(self, other):
+ r"""Add poses (i.e., pose composition): :math:`p_1 \oplus p_2`.
+
+ Parameters
+ ----------
+ other : PoseSE2
+ The other pose
+
+ Returns
+ -------
+ PoseSE2
+ The result of pose composition
+
+ """
+ return PoseSE2(
+ [self[0] + other[0] * np.cos(self[2]) - other[1] * np.sin(self[2]),
+ self[1] + other[0] * np.sin(self[2]) + other[1] * np.cos(self[2])
+ ], neg_pi_to_pi(self[2] + other[2]))
+
+ def __sub__(self, other):
+ r"""Subtract poses (i.e., inverse pose composition): :math:`p_1 \ominus p_2`.
+
+ Parameters
+ ----------
+ other : PoseSE2
+ The other pose
+
+ Returns
+ -------
+ PoseSE2
+ The result of inverse pose composition
+
+ """
+ return PoseSE2([(self[0] - other[0]) * np.cos(other[2]) + (
+ self[1] - other[1]) * np.sin(other[2]),
+ (other[0] - self[0]) * np.sin(other[2]) + (
+ self[1] - other[1]) * np.cos(other[2])],
+ neg_pi_to_pi(self[2] - other[2]))
diff --git a/SLAM/GraphBasedSLAM/graphslam/util.py b/SLAM/GraphBasedSLAM/graphslam/util.py
new file mode 100644
index 0000000000..619aff20af
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/util.py
@@ -0,0 +1,77 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+"""Utility functions used throughout the package.
+
+"""
+
+import numpy as np
+
+
+TWO_PI = 2 * np.pi
+
+
+def neg_pi_to_pi(angle):
+ r"""Normalize ``angle`` to be in :math:`[-\pi, \pi)`.
+
+ Parameters
+ ----------
+ angle : float
+ An angle (in radians)
+
+ Returns
+ -------
+ float
+ The angle normalized to :math:`[-\pi, \pi)`
+
+ """
+ return (angle + np.pi) % (TWO_PI) - np.pi
+
+
+def solve_for_edge_dimensionality(n):
+ r"""Solve for the dimensionality of an edge.
+
+ In a .g2o file, an edge is specified as `` ``, where only the upper triangular portion of the matrix is provided.
+
+ This solves the problem:
+
+ .. math::
+
+ d + \frac{d (d + 1)}{2} = n
+
+ Returns
+ -------
+ int
+ The dimensionality of the edge
+
+ """
+ return int(round(np.sqrt(2 * n + 2.25) - 1.5))
+
+
+def upper_triangular_matrix_to_full_matrix(arr, n):
+ """Given an upper triangular matrix, return the full matrix.
+
+ Parameters
+ ----------
+ arr : np.ndarray
+ The upper triangular portion of the matrix
+ n : int
+ The size of the matrix
+
+ Returns
+ -------
+ mat : np.ndarray
+ The full matrix
+
+ """
+ triu0 = np.triu_indices(n, 0)
+ tril1 = np.tril_indices(n, -1)
+
+ mat = np.zeros((n, n), dtype=float)
+ mat[triu0] = arr
+ mat[tril1] = mat.T[tril1]
+
+ return mat
diff --git a/SLAM/GraphBasedSLAM/graphslam/vertex.py b/SLAM/GraphBasedSLAM/graphslam/vertex.py
new file mode 100644
index 0000000000..6fb1f0d098
--- /dev/null
+++ b/SLAM/GraphBasedSLAM/graphslam/vertex.py
@@ -0,0 +1,67 @@
+# Copyright (c) 2020 Jeff Irion and contributors
+#
+# This file originated from the `graphslam` package:
+#
+# https://github.com/JeffLIrion/python-graphslam
+
+"""A ``Vertex`` class.
+
+"""
+
+import matplotlib.pyplot as plt
+
+
+# pylint: disable=too-few-public-methods
+class Vertex:
+ """A class for representing a vertex in Graph SLAM.
+
+ Parameters
+ ----------
+ vertex_id : int
+ The vertex's unique ID
+ pose : graphslam.pose.se2.PoseSE2
+ The pose associated with the vertex
+ vertex_index : int, None
+ The vertex's index in the graph's ``vertices`` list
+
+ Attributes
+ ----------
+ id : int
+ The vertex's unique ID
+ index : int, None
+ The vertex's index in the graph's ``vertices`` list
+ pose : graphslam.pose.se2.PoseSE2
+ The pose associated with the vertex
+
+ """
+ def __init__(self, vertex_id, pose, vertex_index=None):
+ self.id = vertex_id
+ self.pose = pose
+ self.index = vertex_index
+
+ def to_g2o(self):
+ """Export the vertex to the .g2o format.
+
+ Returns
+ -------
+ str
+ The vertex in .g2o format
+
+ """
+ return "VERTEX_SE2 {} {} {} {}\n".format(self.id, self.pose[0], self.pose[1], self.pose[2])
+
+ def plot(self, color='r', marker='o', markersize=3):
+ """Plot the vertex.
+
+ Parameters
+ ----------
+ color : str
+ The color that will be used to plot the vertex
+ marker : str
+ The marker that will be used to plot the vertex
+ markersize : int
+ The size of the plotted vertex
+
+ """
+ x, y = self.pose.position
+ plt.plot(x, y, color=color, marker=marker, markersize=markersize)
diff --git a/SLAM/ICPMatching/icp_matching.py b/SLAM/ICPMatching/icp_matching.py
new file mode 100644
index 0000000000..2b44de2c07
--- /dev/null
+++ b/SLAM/ICPMatching/icp_matching.py
@@ -0,0 +1,205 @@
+"""
+Iterative Closest Point (ICP) SLAM example
+author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı, Shamil Gemuev
+"""
+
+import math
+
+from mpl_toolkits.mplot3d import Axes3D # noqa: F401 unused import
+import matplotlib.pyplot as plt
+import numpy as np
+
+# ICP parameters
+EPS = 0.0001
+MAX_ITER = 100
+
+show_animation = True
+
+
+def icp_matching(previous_points, current_points):
+ """
+ Iterative Closest Point matching
+ - input
+ previous_points: 2D or 3D points in the previous frame
+ current_points: 2D or 3D points in the current frame
+ - output
+ R: Rotation matrix
+ T: Translation vector
+ """
+ H = None # homogeneous transformation matrix
+
+ dError = np.inf
+ preError = np.inf
+ count = 0
+
+ if show_animation:
+ fig = plt.figure()
+ if previous_points.shape[0] == 3:
+ fig.add_subplot(111, projection='3d')
+
+ while dError >= EPS:
+ count += 1
+
+ if show_animation: # pragma: no cover
+ plot_points(previous_points, current_points, fig)
+ plt.pause(0.1)
+
+ indexes, error = nearest_neighbor_association(previous_points, current_points)
+ Rt, Tt = svd_motion_estimation(previous_points[:, indexes], current_points)
+ # update current points
+ current_points = (Rt @ current_points) + Tt[:, np.newaxis]
+
+ dError = preError - error
+ print("Residual:", error)
+
+ if dError < 0: # prevent matrix H changing, exit loop
+ print("Not Converge...", preError, dError, count)
+ break
+
+ preError = error
+ H = update_homogeneous_matrix(H, Rt, Tt)
+
+ if dError <= EPS:
+ print("Converge", error, dError, count)
+ break
+ elif MAX_ITER <= count:
+ print("Not Converge...", error, dError, count)
+ break
+
+ R = np.array(H[0:-1, 0:-1])
+ T = np.array(H[0:-1, -1])
+
+ return R, T
+
+
+def update_homogeneous_matrix(Hin, R, T):
+
+ r_size = R.shape[0]
+ H = np.zeros((r_size + 1, r_size + 1))
+
+ H[0:r_size, 0:r_size] = R
+ H[0:r_size, r_size] = T
+ H[r_size, r_size] = 1.0
+
+ if Hin is None:
+ return H
+ else:
+ return Hin @ H
+
+
+def nearest_neighbor_association(previous_points, current_points):
+
+ # calc the sum of residual errors
+ delta_points = previous_points - current_points
+ d = np.linalg.norm(delta_points, axis=0)
+ error = sum(d)
+
+ # calc index with nearest neighbor assosiation
+ d = np.linalg.norm(np.repeat(current_points, previous_points.shape[1], axis=1)
+ - np.tile(previous_points, (1, current_points.shape[1])), axis=0)
+ indexes = np.argmin(d.reshape(current_points.shape[1], previous_points.shape[1]), axis=1)
+
+ return indexes, error
+
+
+def svd_motion_estimation(previous_points, current_points):
+ pm = np.mean(previous_points, axis=1)
+ cm = np.mean(current_points, axis=1)
+
+ p_shift = previous_points - pm[:, np.newaxis]
+ c_shift = current_points - cm[:, np.newaxis]
+
+ W = c_shift @ p_shift.T
+ u, s, vh = np.linalg.svd(W)
+
+ R = (u @ vh).T
+ t = pm - (R @ cm)
+
+ return R, t
+
+
+def plot_points(previous_points, current_points, figure):
+ # for stopping simulation with the esc key.
+ plt.gcf().canvas.mpl_connect(
+ 'key_release_event',
+ lambda event: [exit(0) if event.key == 'escape' else None])
+ if previous_points.shape[0] == 3:
+ plt.clf()
+ axes = figure.add_subplot(111, projection='3d')
+ axes.scatter(previous_points[0, :], previous_points[1, :],
+ previous_points[2, :], c="r", marker=".")
+ axes.scatter(current_points[0, :], current_points[1, :],
+ current_points[2, :], c="b", marker=".")
+ axes.scatter(0.0, 0.0, 0.0, c="r", marker="x")
+ figure.canvas.draw()
+ else:
+ plt.cla()
+ plt.plot(previous_points[0, :], previous_points[1, :], ".r")
+ plt.plot(current_points[0, :], current_points[1, :], ".b")
+ plt.plot(0.0, 0.0, "xr")
+ plt.axis("equal")
+
+
+def main():
+ print(__file__ + " start!!")
+
+ # simulation parameters
+ nPoint = 1000
+ fieldLength = 50.0
+ motion = [0.5, 2.0, np.deg2rad(-10.0)] # movement [x[m],y[m],yaw[deg]]
+
+ nsim = 3 # number of simulation
+
+ for _ in range(nsim):
+
+ # previous points
+ px = (np.random.rand(nPoint) - 0.5) * fieldLength
+ py = (np.random.rand(nPoint) - 0.5) * fieldLength
+ previous_points = np.vstack((px, py))
+
+ # current points
+ cx = [math.cos(motion[2]) * x - math.sin(motion[2]) * y + motion[0]
+ for (x, y) in zip(px, py)]
+ cy = [math.sin(motion[2]) * x + math.cos(motion[2]) * y + motion[1]
+ for (x, y) in zip(px, py)]
+ current_points = np.vstack((cx, cy))
+
+ R, T = icp_matching(previous_points, current_points)
+ print("R:", R)
+ print("T:", T)
+
+
+def main_3d_points():
+ print(__file__ + " start!!")
+
+ # simulation parameters for 3d point set
+ nPoint = 1000
+ fieldLength = 50.0
+ motion = [0.5, 2.0, -5, np.deg2rad(-10.0)] # [x[m],y[m],z[m],roll[deg]]
+
+ nsim = 3 # number of simulation
+
+ for _ in range(nsim):
+
+ # previous points
+ px = (np.random.rand(nPoint) - 0.5) * fieldLength
+ py = (np.random.rand(nPoint) - 0.5) * fieldLength
+ pz = (np.random.rand(nPoint) - 0.5) * fieldLength
+ previous_points = np.vstack((px, py, pz))
+
+ # current points
+ cx = [math.cos(motion[3]) * x - math.sin(motion[3]) * z + motion[0]
+ for (x, z) in zip(px, pz)]
+ cy = [y + motion[1] for y in py]
+ cz = [math.sin(motion[3]) * x + math.cos(motion[3]) * z + motion[2]
+ for (x, z) in zip(px, pz)]
+ current_points = np.vstack((cx, cy, cz))
+
+ R, T = icp_matching(previous_points, current_points)
+ print("R:", R)
+ print("T:", T)
+
+
+if __name__ == '__main__':
+ main()
+ main_3d_points()
diff --git a/SLAM/PoseOptimizationSLAM/README.md b/SLAM/PoseOptimizationSLAM/README.md
deleted file mode 100644
index 612fa5186d..0000000000
--- a/SLAM/PoseOptimizationSLAM/README.md
+++ /dev/null
@@ -1,9 +0,0 @@
-# How to use
-
-1. Download data
-
->$ python data_downloader.py
-
-2. run SLAM
-
->$ python pose_optimization_slam.py
diff --git a/SLAM/PoseOptimizationSLAM/data_downloader.py b/SLAM/PoseOptimizationSLAM/data_downloader.py
deleted file mode 100644
index d1b8a2c23b..0000000000
--- a/SLAM/PoseOptimizationSLAM/data_downloader.py
+++ /dev/null
@@ -1,28 +0,0 @@
-"""
-
-Data down loader for pose optimization
-
-author: Atsushi Sakai
-
-"""
-
-
-import subprocess
-def main():
- print("start!!")
-
- cmd = "wget https://www.dropbox.com/s/vcz8cag7bo0zlaj/input_INTEL_g2o.g2o?dl=0 -O intel.g2o -nc"
- subprocess.call(cmd, shell=True)
-
- cmd = "wget https://www.dropbox.com/s/d8fcn1jg1mebx8f/input_MITb_g2o.g2o?dl=0 -O mit_killian.g2o -nc"
-
- subprocess.call(cmd, shell=True)
- cmd = "wget https://www.dropbox.com/s/gmdzo74b3tzvbrw/input_M3500_g2o.g2o?dl=0 -O manhattan3500.g2o -nc"
- subprocess.call(cmd, shell=True)
-
- print("done!!")
-
-
-if __name__ == '__main__':
- main()
-
diff --git a/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py b/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py
deleted file mode 100644
index 764b0f5e73..0000000000
--- a/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py
+++ /dev/null
@@ -1,290 +0,0 @@
-"""
-
-2D (x, y, yaw) pose optimization SLAM
-
-author: Atsushi Sakai
-
-Ref:
-- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM)
-
-- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o)
-
-"""
-
-import sys
-import time
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-from scipy import sparse
-from scipy.sparse import linalg
-
-
-class Optimizer2D:
-
- def __init__(self):
- self.verbose = False
- self.animation = False
- self.p_lambda = 0.0
- self.init_w = 1e10
- self.stop_thre = 1e-3
- self.dim = 3 # state dimension
-
- def optimize_path(self, nodes, consts, max_iter, min_iter):
-
- graph_nodes = nodes[:]
- prev_cost = sys.float_info.max
-
- for i in range(max_iter):
- start = time.time()
- cost, graph_nodes = self.optimize_path_one_step(
- graph_nodes, consts)
- elapsed = time.time() - start
- if self.verbose:
- print("step ", i, " cost: ", cost, " time:", elapsed, "s")
-
- # check convergence
- if (i > min_iter) and (prev_cost - cost < self.stop_thre):
- if self.verbose:
- print("converged:", prev_cost
- - cost, " < ", self.stop_thre)
- break
- prev_cost = cost
-
- if self.animation:
- plt.cla()
- plot_nodes(nodes, color="-b")
- plot_nodes(graph_nodes)
- plt.axis("equal")
- plt.pause(1.0)
-
- return graph_nodes
-
- def optimize_path_one_step(self, graph_nodes, constraints):
-
- indlist = [i for i in range(self.dim)]
- numnodes = len(graph_nodes)
- bf = np.zeros(numnodes * self.dim)
- tripletList = TripletList()
-
- for con in constraints:
- ida = con.id1
- idb = con.id2
- assert 0 <= ida and ida < numnodes, "ida is invalid"
- assert 0 <= idb and idb < numnodes, "idb is invalid"
- r, Ja, Jb = self.calc_error(
- graph_nodes[ida], graph_nodes[idb], con.t)
-
- trJaInfo = Ja.transpose() @ con.info_mat
- trJaInfoJa = trJaInfo @ Ja
- trJbInfo = Jb.transpose() @ con.info_mat
- trJbInfoJb = trJbInfo @ Jb
- trJaInfoJb = trJaInfo @ Jb
-
- for k in indlist:
- for m in indlist:
- tripletList.push_back(
- ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m])
- tripletList.push_back(
- idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m])
- tripletList.push_back(
- ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m])
- tripletList.push_back(
- idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k])
-
- bf[ida * self.dim: ida * self.dim + 3] += trJaInfo @ r
- bf[idb * self.dim: idb * self.dim + 3] += trJbInfo @ r
-
- for k in indlist:
- tripletList.push_back(k, k, self.init_w)
-
- for i in range(self.dim * numnodes):
- tripletList.push_back(i, i, self.p_lambda)
-
- mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)),
- shape=(numnodes * self.dim, numnodes * self.dim))
-
- x = linalg.spsolve(mat.tocsr(), -bf)
-
- out_nodes = []
- for i in range(len(graph_nodes)):
- u_i = i * self.dim
- pos = Pose2D(
- graph_nodes[i].x + x[u_i],
- graph_nodes[i].y + x[u_i + 1],
- graph_nodes[i].theta + x[u_i + 2]
- )
- out_nodes.append(pos)
-
- cost = self.calc_global_cost(out_nodes, constraints)
-
- return cost, out_nodes
-
- def calc_global_cost(self, nodes, constraints):
- cost = 0.0
- for c in constraints:
- diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t)
- cost += diff.transpose() @ c.info_mat @ diff
-
- return cost
-
- def error_func(self, pa, pb, t):
- ba = self.calc_constraint_pose(pb, pa)
- error = np.array([ba.x - t.x,
- ba.y - t.y,
- self.pi2pi(ba.theta - t.theta)])
- return error
-
- def calc_constraint_pose(self, l, r):
- diff = np.array([l.x - r.x, l.y - r.y, l.theta - r.theta])
- v = self.rot_mat_2d(-r.theta) @ diff
- v[2] = self.pi2pi(l.theta - r.theta)
- return Pose2D(v[0], v[1], v[2])
-
- def rot_mat_2d(self, theta):
- return np.array([[math.cos(theta), -math.sin(theta), 0.0],
- [math.sin(theta), math.cos(theta), 0.0],
- [0.0, 0.0, 1.0]
- ])
-
- def calc_error(self, pa, pb, t):
- e0 = self.error_func(pa, pb, t)
- dx = pb.x - pa.x
- dy = pb.y - pa.y
- dxdt = -math.sin(pa.theta) * dx + math.cos(pa.theta) * dy
- dydt = -math.cos(pa.theta) * dx - math.sin(pa.theta) * dy
- Ja = np.array([[-math.cos(pa.theta), -math.sin(pa.theta), dxdt],
- [math.sin(pa.theta), -math.cos(pa.theta), dydt],
- [0.0, 0.0, -1.0]
- ])
- Jb = np.array([[math.cos(pa.theta), math.sin(pa.theta), 0.0],
- [-math.sin(pa.theta), math.cos(pa.theta), 0.0],
- [0.0, 0.0, 1.0]
- ])
- return e0, Ja, Jb
-
- def pi2pi(self, rad):
-
- val = math.fmod(rad, 2.0 * math.pi)
- if val > math.pi:
- val -= 2.0 * math.pi
- elif val < -math.pi:
- val += 2.0 * math.pi
-
- return val
-
-
-class TripletList:
-
- def __init__(self):
- self.row = []
- self.col = []
- self.data = []
-
- def push_back(self, irow, icol, idata):
- self.row.append(irow)
- self.col.append(icol)
- self.data.append(idata)
-
-
-class Pose2D:
-
- def __init__(self, x, y, theta):
- self.x = x
- self.y = y
- self.theta = theta
-
-
-class Constrant2D:
-
- def __init__(self, id1, id2, t, info_mat):
- self.id1 = id1
- self.id2 = id2
- self.t = t
- self.info_mat = info_mat
-
-
-def plot_nodes(nodes, color ="-r", label = ""):
- x, y = [], []
- for n in nodes:
- x.append(n.x)
- y.append(n.y)
- plt.plot(x, y, color, label=label)
-
-
-def load_data(fname):
- nodes, consts = [], []
-
- for line in open(fname):
- sline = line.split()
- tag = sline[0]
-
- if tag == "VERTEX_SE2":
- data_id = int(sline[1])
- x = float(sline[2])
- y = float(sline[3])
- theta = float(sline[4])
- nodes.append(Pose2D(x, y, theta))
- elif tag == "EDGE_SE2":
- id1 = int(sline[1])
- id2 = int(sline[2])
- x = float(sline[3])
- y = float(sline[4])
- th = float(sline[5])
- c1 = float(sline[6])
- c2 = float(sline[7])
- c3 = float(sline[8])
- c4 = float(sline[9])
- c5 = float(sline[10])
- c6 = float(sline[11])
- t = Pose2D(x, y, th)
- info_mat = np.array([[c1, c2, c3],
- [c2, c4, c5],
- [c3, c5, c6]
- ])
- consts.append(Constrant2D(id1, id2, t, info_mat))
-
- print("n_nodes:", len(nodes))
- print("n_consts:", len(consts))
-
- return nodes, consts
-
-
-def main():
- print("start!!")
-
- fnames = ["intel.g2o",
- "manhattan3500.g2o",
- "mit_killian.g2o"
- ]
-
- max_iter = 20
- min_iter = 3
-
- # parameter setting
- optimizer = Optimizer2D()
- optimizer.p_lambda = 1e-6
- optimizer.verbose = True
- optimizer.animation = True
-
- for f in fnames:
- nodes, consts = load_data(f)
-
- start = time.time()
- final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter)
- print("elapsed_time", time.time() - start, "sec")
-
- # plotting
- plt.cla()
- plot_nodes(nodes, color="-b", label="before")
- plot_nodes(final_nodes, label="after")
- plt.axis("equal")
- plt.grid(True)
- plt.legend()
- plt.pause(3.0)
-
- print("done!!")
-
-
-if __name__ == '__main__':
- main()
diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py
deleted file mode 100644
index 73651d8ec5..0000000000
--- a/SLAM/iterative_closest_point/iterative_closest_point.py
+++ /dev/null
@@ -1,159 +0,0 @@
-"""
-Iterative Closest Point (ICP) SLAM example
-author: Atsushi Sakai (@Atsushi_twi)
-"""
-
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-
-# ICP parameters
-EPS = 0.0001
-MAXITER = 100
-
-show_animation = True
-
-
-def ICP_matching(ppoints, cpoints):
- """
- Iterative Closest Point matching
- - input
- ppoints: 2D points in the previous frame
- cpoints: 2D points in the current frame
- - output
- R: Rotation matrix
- T: Translation vector
- """
- H = None # homogeneous transformation matrix
-
- dError = 1000.0
- preError = 1000.0
- count = 0
-
- while dError >= EPS:
- count += 1
-
- if show_animation: # pragma: no cover
- plt.cla()
- plt.plot(ppoints[0, :], ppoints[1, :], ".r")
- plt.plot(cpoints[0, :], cpoints[1, :], ".b")
- plt.plot(0.0, 0.0, "xr")
- plt.axis("equal")
- plt.pause(1.0)
-
- inds, error = nearest_neighbor_assosiation(ppoints, cpoints)
- Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints)
-
- # update current points
- cpoints = (Rt @ cpoints) + Tt[:, np.newaxis]
-
- H = update_homogeneous_matrix(H, Rt, Tt)
-
- dError = abs(preError - error)
- preError = error
- print("Residual:", error)
-
- if dError <= EPS:
- print("Converge", error, dError, count)
- break
- elif MAXITER <= count:
- print("Not Converge...", error, dError, count)
- break
-
- R = np.array(H[0:2, 0:2])
- T = np.array(H[0:2, 2])
-
- return R, T
-
-
-def update_homogeneous_matrix(Hin, R, T):
-
- H = np.zeros((3, 3))
-
- H[0, 0] = R[0, 0]
- H[1, 0] = R[1, 0]
- H[0, 1] = R[0, 1]
- H[1, 1] = R[1, 1]
- H[2, 2] = 1.0
-
- H[0, 2] = T[0]
- H[1, 2] = T[1]
-
- if Hin is None:
- return H
- else:
- return Hin @ H
-
-
-def nearest_neighbor_assosiation(ppoints, cpoints):
-
- # calc the sum of residual errors
- dcpoints = ppoints - cpoints
- d = np.linalg.norm(dcpoints, axis=0)
- error = sum(d)
-
- # calc index with nearest neighbor assosiation
- inds = []
- for i in range(cpoints.shape[1]):
- minid = -1
- mind = float("inf")
- for ii in range(ppoints.shape[1]):
- d = np.linalg.norm(ppoints[:, ii] - cpoints[:, i])
-
- if mind >= d:
- mind = d
- minid = ii
-
- inds.append(minid)
-
- return inds, error
-
-
-def SVD_motion_estimation(ppoints, cpoints):
-
- pm = np.mean(ppoints, axis=1)
- cm = np.mean(cpoints, axis=1)
-
- pshift = ppoints - pm[:, np.newaxis]
- cshift = cpoints - cm[:, np.newaxis]
-
- W = cshift @ pshift.T
- u, s, vh = np.linalg.svd(W)
-
- R = (u @ vh).T
- t = pm - (R @ cm)
-
- return R, t
-
-
-def main():
- print(__file__ + " start!!")
-
- # simulation parameters
- nPoint = 10
- fieldLength = 50.0
- motion = [0.5, 2.0, np.deg2rad(-10.0)] # movement [x[m],y[m],yaw[deg]]
-
- nsim = 3 # number of simulation
-
- for _ in range(nsim):
-
- # previous points
- px = (np.random.rand(nPoint) - 0.5) * fieldLength
- py = (np.random.rand(nPoint) - 0.5) * fieldLength
- ppoints = np.vstack((px, py))
-
- # current points
- cx = [math.cos(motion[2]) * x - math.sin(motion[2]) * y + motion[0]
- for (x, y) in zip(px, py)]
- cy = [math.sin(motion[2]) * x + math.cos(motion[2]) * y + motion[1]
- for (x, y) in zip(px, py)]
- cpoints = np.vstack((cx, cy))
-
- R, T = ICP_matching(ppoints, cpoints)
- print("R:", R)
- print("T:", T)
-
-
-if __name__ == '__main__':
- main()
\ No newline at end of file
diff --git a/__init__.py b/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/appveyor.yml b/appveyor.yml
index 6cfe488378..72d89acf11 100644
--- a/appveyor.yml
+++ b/appveyor.yml
@@ -1,18 +1,21 @@
+os: Visual Studio 2022
+
environment:
global:
# SDK v7.0 MSVC Express 2008's SetEnv.cmd script will fail if the
# /E:ON and /V:ON options are not enabled in the batch script intepreter
- # See: http://stackoverflow.com/a/13751649/163740
+ # See: https://stackoverflow.com/a/13751649/163740
CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd"
-
matrix:
- - PYTHON_VERSION: 3.6
- MINICONDA: "C:\\Miniconda36-x64"
+ - PYTHON_DIR: C:\Python313-x64
-init:
- - "ECHO %MINICONDA% %PYTHON_VERSION% %PYTHON_ARCH%"
+branches:
+ only:
+ - master
+init:
+ - "ECHO %PYTHON_DIR%"
install:
# If there is a newer build queued for the same PR, cancel this one.
@@ -27,27 +30,15 @@ install:
- ECHO "Filesystem root:"
- ps: "ls \"C:/\""
- - ECHO "Installed SDKs:"
- - ps: "ls \"C:/Program Files/Microsoft SDKs/Windows\""
-
# Prepend newly installed Python to the PATH of this build (this cannot be
# done from inside the powershell script as it would require to restart
# the parent CMD process).
- - "SET PATH=%MINICONDA%;%MINICONDA%\\Scripts;%PATH%"
- - conda config --set always_yes yes --set changeps1 no
- - conda update -q conda
- - conda info -a
+ - SET PATH=%PYTHON_DIR%;%PYTHON_DIR%\\Scripts;%PATH%
+ - SET PATH=%PYTHON%;%PYTHON%\Scripts;%PYTHON%\Library\bin;%PATH%
+ - SET PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\bin
- "python -m pip install --upgrade pip"
- #- conda install numpy==1.15
- #- conda install scipy
- #- conda install matplotlib
- #- conda install pandas
- #- conda config --add channels conda-forge
- #- conda install -c conda-forge lapack
- #- conda install -c cvxgrp cvxpy
- #- conda install coveralls
- - conda env create -f C:\\projects\pythonrobotics\environment.yml
- - activate python_robotics
+ - "python -m pip install -r requirements/requirements.txt"
+ - "python -m pip install pytest-xdist"
# Check that we have the expected version and architecture for Python
- "python --version"
@@ -56,4 +47,4 @@ install:
build: off
test_script:
- - "python -Wignore -m unittest discover tests"
+ - "pytest tests -n auto -Werror --durations=0"
diff --git a/docs/Makefile b/docs/Makefile
index 9296811e02..ae495eb36d 100644
--- a/docs/Makefile
+++ b/docs/Makefile
@@ -2,7 +2,8 @@
#
# You can set these variables from the command line.
-SPHINXOPTS =
+# SPHINXOPTS with -W means turn warnings into errors to fail the build when warnings are present.
+SPHINXOPTS = -W
SPHINXBUILD = sphinx-build
SPHINXPROJ = PythonRobotics
SOURCEDIR = .
diff --git a/docs/README.md b/docs/README.md
index 1c6eea4a65..fb7d4cc3bc 100644
--- a/docs/README.md
+++ b/docs/README.md
@@ -8,7 +8,7 @@ This folder contains documentation for the Python Robotics project.
#### Install Sphinx and Theme
```
-pip install sphinx sphinx-autobuild sphinx-rtd-theme
+pip install sphinx sphinx-autobuild sphinx-rtd-theme sphinx_rtd_dark_mode sphinx_copybutton sphinx_rtd_dark_mode
```
#### Building the Docs
@@ -24,14 +24,6 @@ if you want to building each time a file is changed:
sphinx-autobuild . _build/html
```
-### Jupyter notebook integration
-
-When you want to generate rst files from each jupyter notebooks,
-
-you can use
-
-```
-cd path/to/docs
-python jupyternotebook2rst.py
-```
+#### Check the generated doc
+Open the index.html file under docs/_build/
diff --git a/docs/_static/custom.css b/docs/_static/custom.css
new file mode 100644
index 0000000000..51c98d21ce
--- /dev/null
+++ b/docs/_static/custom.css
@@ -0,0 +1,23 @@
+/*
+ * Necessary parts from
+ * Sphinx stylesheet -- basic theme
+ * absent from sphinx_rtd_theme
+ * (see https://github.com/readthedocs/sphinx_rtd_theme/issues/301)
+ * Ref https://github.com/PyAbel/PyAbel/commit/7e4dee81eac3f0a6955a85a4a42cf04a4e0d995c
+ */
+
+/* -- math display ---------------------------------------------------------- */
+
+span.eqno {
+ float: right;
+}
+
+span.eqno a.headerlink {
+ position: absolute;
+ z-index: 1;
+ visibility: hidden;
+}
+
+div.math:hover a.headerlink {
+ visibility: visible;
+}
diff --git a/docs/_static/img/doc_ci.png b/docs/_static/img/doc_ci.png
new file mode 100644
index 0000000000..a9a73f7e92
Binary files /dev/null and b/docs/_static/img/doc_ci.png differ
diff --git a/docs/_static/img/source_link_1.png b/docs/_static/img/source_link_1.png
new file mode 100644
index 0000000000..53febda7cb
Binary files /dev/null and b/docs/_static/img/source_link_1.png differ
diff --git a/docs/_static/img/source_link_2.png b/docs/_static/img/source_link_2.png
new file mode 100644
index 0000000000..d5647cac60
Binary files /dev/null and b/docs/_static/img/source_link_2.png differ
diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html
new file mode 100644
index 0000000000..4b5b278932
--- /dev/null
+++ b/docs/_templates/layout.html
@@ -0,0 +1,17 @@
+{% extends "!layout.html" %}
+
+{% block sidebartitle %}
+{{ super() }}
+
+
+
+
+{% endblock %}
diff --git a/docs/conf.py b/docs/conf.py
index 7422e2b106..eeabab11b1 100644
--- a/docs/conf.py
+++ b/docs/conf.py
@@ -1,10 +1,9 @@
-# -*- coding: utf-8 -*-
#
# Configuration file for the Sphinx documentation builder.
#
# This file does only contain a selection of the most common options. For a
# full list see the documentation:
-# http://www.sphinx-doc.org/en/master/config
+# https://www.sphinx-doc.org/en/master/config
# -- Path setup --------------------------------------------------------------
@@ -13,14 +12,16 @@
# documentation root, use os.path.abspath to make it absolute, like shown here.
#
import os
-# import sys
-# sys.path.insert(0, os.path.abspath('.'))
+import sys
+from pathlib import Path
+
+sys.path.insert(0, os.path.abspath('../'))
# -- Project information -----------------------------------------------------
project = 'PythonRobotics'
-copyright = '2018, Atsushi Sakai'
+copyright = '2018-now, Atsushi Sakai'
author = 'Atsushi Sakai'
# The short X.Y version
@@ -39,10 +40,15 @@
# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom
# ones.
extensions = [
+ 'matplotlib.sphinxext.plot_directive',
'sphinx.ext.autodoc',
'sphinx.ext.mathjax',
- 'sphinx.ext.viewcode',
- 'sphinx.ext.viewcode',
+ 'sphinx.ext.linkcode',
+ 'sphinx.ext.napoleon',
+ 'sphinx.ext.imgconverter',
+ 'IPython.sphinxext.ipython_console_highlighting',
+ 'sphinx_copybutton',
+ 'sphinx_rtd_dark_mode',
]
# Add any paths that contain templates here, relative to this directory.
@@ -52,7 +58,7 @@
# You can specify multiple suffix as a list of string:
#
# source_suffix = ['.rst', '.md']
-source_suffix = '.rst'
+source_suffix = '_main.rst'
# The master toctree document.
master_doc = 'index'
@@ -62,7 +68,7 @@
#
# This is also used if you do content translation via gettext catalogs.
# Usually you set "language" from the command line for these cases.
-language = None
+language = "en"
# List of patterns, relative to source directory, that match files and
# directories to ignore when looking for source files.
@@ -83,7 +89,7 @@
if on_rtd:
html_theme = 'default'
else:
- html_theme = 'sphinx_rtd_theme'
+ html_theme = 'sphinx_rtd_light_them'
# Theme options are theme-specific and customize the look and feel of a theme
# further. For a list of options available for each theme, see the
@@ -94,11 +100,24 @@
'display_version': False,
}
+# replace "view page source" with "edit on github" in Read The Docs theme
+# * https://github.com/readthedocs/sphinx_rtd_theme/issues/529
+html_context = {
+ 'display_github': True,
+ 'github_user': 'AtsushiSakai',
+ 'github_repo': 'PythonRobotics',
+ 'github_version': 'master',
+ "conf_py_path": "/docs/",
+ "source_suffix": source_suffix,
+}
+
# Add any paths that contain custom static files (such as style sheets) here,
# relative to this directory. They are copied after the builtin static files,
# so a file named "default.css" will overwrite the builtin "default.css".
html_static_path = ['_static']
+html_css_files = ['custom.css']
+
# Custom sidebar templates, must be a dictionary that maps document names
# to template names.
#
@@ -167,4 +186,45 @@
]
-# -- Extension configuration -------------------------------------------------
+# -- linkcode setting -------------------------------------------------
+
+import inspect
+import os
+import sys
+import functools
+
+GITHUB_REPO = "https://github.com/AtsushiSakai/PythonRobotics"
+GITHUB_BRANCH = "master"
+
+
+def linkcode_resolve(domain, info):
+ if domain != "py":
+ return None
+
+ modname = info["module"]
+ fullname = info["fullname"]
+
+ try:
+ module = __import__(modname, fromlist=[fullname])
+ obj = functools.reduce(getattr, fullname.split("."), module)
+ except (ImportError, AttributeError):
+ return None
+
+ try:
+ srcfile = inspect.getsourcefile(obj)
+ srcfile = get_relative_path_from_parent(srcfile, "PythonRobotics")
+ lineno = inspect.getsourcelines(obj)[1]
+ except Exception:
+ return None
+
+ return f"{GITHUB_REPO}/blob/{GITHUB_BRANCH}/{srcfile}#L{lineno}"
+
+
+def get_relative_path_from_parent(file_path: str, parent_dir: str):
+ path = Path(file_path).resolve()
+
+ try:
+ parent_path = next(p for p in path.parents if p.name == parent_dir)
+ return str(path.relative_to(parent_path))
+ except StopIteration:
+ raise ValueError(f"Parent directory '{parent_dir}' not found in {file_path}")
diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt
new file mode 100644
index 0000000000..b29f4ba289
--- /dev/null
+++ b/docs/doc_requirements.txt
@@ -0,0 +1,6 @@
+sphinx == 7.2.6 # For sphinx documentation
+sphinx_rtd_theme == 2.0.0
+IPython == 8.20.0 # For sphinx documentation
+sphinxcontrib-napoleon == 0.7 # For auto doc
+sphinx-copybutton
+sphinx-rtd-dark-mode
diff --git a/docs/getting_started.rst b/docs/getting_started.rst
deleted file mode 100644
index 2f60557f38..0000000000
--- a/docs/getting_started.rst
+++ /dev/null
@@ -1,30 +0,0 @@
-.. _getting_started:
-
-Getting Started
-===============
-
-Requirements
--------------
-
-- Python 3.6.x
-- numpy
-- scipy
-- matplotlib
-- pandas
-- `cvxpy`_
-
-.. _cvxpy: http://www.cvxpy.org/en/latest/
-
-
-How to use
-----------
-
-1. Install the required libraries. You can use environment.yml with
- conda command.
-
-2. Clone this repo.
-
-3. Execute python script in each directory.
-
-4. Add star to this repo if you like it 😃.
-
diff --git a/docs/index.rst b/docs/index.rst
deleted file mode 100644
index e8e6052879..0000000000
--- a/docs/index.rst
+++ /dev/null
@@ -1,53 +0,0 @@
-.. PythonRobotics documentation master file, created by
- sphinx-quickstart on Sat Sep 15 13:15:55 2018.
- You can adapt this file completely to your liking, but it should at least
- contain the root `toctree` directive.
-
-Welcome to PythonRobotics's documentation!
-==========================================
-
-Python codes for robotics algorithm. The project is on `GitHub`_.
-
-This is a Python code collection of robotics algorithms, especially for autonomous navigation.
-
-Features:
-
-1. Easy to read for understanding each algorithm's basic idea.
-
-2. Widely used and practical algorithms are selected.
-
-3. Minimum dependency.
-
-See this paper for more details:
-
-- `[1808.10703] PythonRobotics: a Python code collection of robotics
- algorithms`_ (`BibTeX`_)
-
-
-.. _`[1808.10703] PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703
-.. _BibTeX: https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib
-.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics
-
-
-.. toctree::
- :maxdepth: 2
- :caption: Guide
-
- getting_started
- modules/introduction
- modules/localization
- modules/mapping
- modules/slam
- modules/path_planning
- modules/path_tracking
- modules/arm_navigation
- modules/aerial_navigation
- modules/appendix
-
-
-Indices and tables
-==================
-
-* :ref:`genindex`
-* :ref:`modindex`
-* :ref:`search`
diff --git a/docs/index_main.rst b/docs/index_main.rst
new file mode 100644
index 0000000000..65634f32e8
--- /dev/null
+++ b/docs/index_main.rst
@@ -0,0 +1,57 @@
+.. PythonRobotics documentation master file, created by
+ sphinx-quickstart on Sat Sep 15 13:15:55 2018.
+ You can adapt this file completely to your liking, but it should at least
+ contain the root `toctree` directive.
+
+Welcome to PythonRobotics's documentation!
+==========================================
+
+"PythonRobotics" is a Python code collections and textbook
+(This document) for robotics algorithm, which is developed on `GitHub`_.
+
+See this section (:ref:`What is PythonRobotics?`) for more details of this project.
+
+This project is `the one of the most popular open-source software (OSS) in
+the field of robotics on GitHub`_.
+This is `user comments about this project`_, and
+this graph shows GitHub star history of this project:
+
+.. image:: https://api.star-history.com/svg?repos=AtsushiSakai/PythonRobotics&type=Date
+ :alt: Star History
+ :width: 80%
+ :align: center
+
+
+.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics
+.. _`user comments about this project`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md
+.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE
+.. _`the one of the most popular open-source software (OSS) in the field of robotics on GitHub`: https://github.com/topics/robotics
+
+----------------------------------
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Table of Contents
+
+ modules/0_getting_started/0_getting_started
+ modules/1_introduction/introduction
+ modules/2_localization/localization
+ modules/3_mapping/mapping
+ modules/4_slam/slam
+ modules/5_path_planning/path_planning
+ modules/6_path_tracking/path_tracking
+ modules/7_arm_navigation/arm_navigation
+ modules/8_aerial_navigation/aerial_navigation
+ modules/9_bipedal/bipedal
+ modules/10_inverted_pendulum/inverted_pendulum
+ modules/13_mission_planning/mission_planning
+ modules/11_utils/utils
+ modules/12_appendix/appendix
+
+
+Indices and tables
+==================
+
+* :ref:`genindex`
+* :ref:`modindex`
+* :ref:`search`
diff --git a/docs/jupyternotebook2rst.py b/docs/jupyternotebook2rst.py
deleted file mode 100644
index 3db67244b6..0000000000
--- a/docs/jupyternotebook2rst.py
+++ /dev/null
@@ -1,93 +0,0 @@
-"""
-
-Jupyter notebook converter to rst file
-
-author: Atsushi Sakai
-
-"""
-import subprocess
-import os.path
-import os
-import glob
-
-
-NOTEBOOK_DIR = "../"
-
-
-def get_notebook_path_list(ndir):
- path = glob.glob(ndir + "**/*.ipynb", recursive=True)
- return path
-
-
-def convert_rst(rstpath):
-
- with open(rstpath, "r") as bfile:
- filedata = bfile.read()
-
- # convert from code directive to code-block
- # because showing code in Sphinx
- before = ".. code:: ipython3"
- after = ".. code-block:: ipython3"
- filedata = filedata.replace(before, after)
-
- with open(rstpath, "w") as afile:
- afile.write(filedata)
-
-
-def generate_rst(npath):
- print("====Start generating rst======")
-
- # generate dir
- dirpath = os.path.dirname(npath)
- # print(dirpath)
-
- rstpath = os.path.abspath("./modules/" + npath[3:-5] + "rst")
- # print(rstpath)
-
- basename = os.path.basename(rstpath)
-
- cmd = "jupyter nbconvert --to rst "
- cmd += npath
- print(cmd)
- subprocess.call(cmd, shell=True)
-
- rstpath = dirpath + "/" + basename
- convert_rst(rstpath)
-
- # clean up old files
- cmd = "rm -rf "
- cmd += "./modules/"
- cmd += basename[:-4]
- cmd += "*"
- # print(cmd)
- subprocess.call(cmd, shell=True)
-
- # move files to module dir
- cmd = "mv "
- cmd += dirpath
- cmd += "/*.rst ./modules/"
- print(cmd)
- subprocess.call(cmd, shell=True)
-
- cmd = "mv "
- cmd += dirpath
- cmd += "/*_files ./modules/"
- print(cmd)
- subprocess.call(cmd, shell=True)
-
-
-def main():
- print("start!!")
-
- notebook_path_list = get_notebook_path_list(NOTEBOOK_DIR)
- # print(notebook_path_list)
-
- for npath in notebook_path_list:
- if "template" not in npath:
- generate_rst(npath)
-
- print("done!!")
-
-
-if __name__ == '__main__':
- main()
diff --git a/docs/make.bat b/docs/make.bat
index 6aab964dcc..07dcebea41 100644
--- a/docs/make.bat
+++ b/docs/make.bat
@@ -22,7 +22,7 @@ if errorlevel 9009 (
echo.may add the Sphinx directory to PATH.
echo.
echo.If you don't have Sphinx installed, grab it from
- echo.http://sphinx-doc.org/
+ echo.https://sphinx-doc.org/
exit /b 1
)
diff --git a/docs/modules/0_getting_started/0_getting_started_main.rst b/docs/modules/0_getting_started/0_getting_started_main.rst
new file mode 100644
index 0000000000..cb2cba4784
--- /dev/null
+++ b/docs/modules/0_getting_started/0_getting_started_main.rst
@@ -0,0 +1,13 @@
+.. _`getting started`:
+
+Getting Started
+===============
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ 1_what_is_python_robotics
+ 2_how_to_run_sample_codes
+ 3_how_to_contribute
+ 4_how_to_read_textbook
diff --git a/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst
new file mode 100644
index 0000000000..2a7bd574f0
--- /dev/null
+++ b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst
@@ -0,0 +1,130 @@
+.. _`What is PythonRobotics?`:
+
+What is PythonRobotics?
+------------------------
+
+This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms.
+These codes are developed under `MIT license`_ and on `GitHub`_.
+
+.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics
+.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE
+
+This project has three main philosophies below:
+
+Philosophy 1. Easy to understand each algorithm's basic idea.
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The goal is for beginners in robotics to understand the basic ideas behind each algorithm.
+
+`Python`_ programming language is adopted in this project to achieve the goal.
+Python is a high-level programming language that is easy to read and write.
+If the code is not easy to read, it would be difficult to achieve our goal of
+allowing beginners to understand the algorithms.
+Python has great libraries for matrix operation, mathematical and scientific operation,
+and visualization, which makes code more readable because such operations
+don’t need to be re-implemented.
+Having the core Python packages allows the user to focus on the algorithms,
+rather than the implementations.
+
+PythonRobotics provides not only the code but also intuitive animations that
+visually demonstrate the process and behavior of each algorithm over time.
+This is an example of an animation gif file that shows the process of the
+path planning in a highway scenario for autonomous vehicle.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_velocity_keeping_frenet_path.gif
+
+This animation is a gif file and is created using the `Matplotlib`_ library.
+All animation gif files are stored in the `PythonRoboticsGifs`_ repository and
+all animation movies are also uploaded to this `YouTube channel`_.
+
+PythonRobotics also provides a textbook that explains the basic ideas of each algorithm.
+The PythonRobotics textbook allows you to learn fundamental algorithms used in
+robotics with minimal mathematical formulas and textual explanations,
+based on PythonRobotics’ sample codes and animations.
+The contents of this document, like the code, are managed in the PythonRobotics
+`GitHub`_ repository and converted into HTML-based online documents using `Sphinx`_,
+which is a Python-based documentation builder.
+Please refer to this section ":ref:`How to read this textbook`" for information on
+how to read this document for learning.
+
+
+.. _`Python`: https://www.python.org/
+.. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs
+.. _`YouTube channel`: https://youtube.com/playlist?list=PL12URV8HFpCozuz0SDxke6b2ae5UZvIwa&si=AH2fNPPYufPtK20S
+
+
+Philosophy 2. Widely used and practical algorithms are selected.
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The second philosophy is that implemented algorithms have to be practical
+and widely used in both academia and industry.
+We believe learning these algorithms will be useful in many applications.
+For example, Kalman filters and particle filter for localization,
+grid mapping for mapping,
+dynamic programming based approaches and sampling based approaches for path planning,
+and optimal control based approach for path tracking.
+These algorithms are implemented and explained in the textbook in this project.
+
+Philosophy 3. Minimum dependency.
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Each sample code of PythonRobotics is written in Python3 and only depends on
+some standard modules for readability and ease to setup and use.
+
+
+.. _`Requirements`:
+
+Requirements
+============
+
+PythonRobotics depends only on the following five libraries,
+including Python itself, to run each sample code.
+
+- `Python 3.12.x`_ (for Python runtime)
+- `NumPy`_ (for matrix operation)
+- `SciPy`_ (for scientific operation)
+- `cvxpy`_ (for convex optimization)
+- `Matplotlib`_ (for visualization)
+
+If you only need to run the code, the five libraries mentioned above are sufficient.
+However, for code development or creating documentation for the textbook,
+the following additional libraries are required.
+
+- `pytest`_ (for unit tests)
+- `pytest-xdist`_ (for parallel unit tests)
+- `mypy`_ (for type check)
+- `Sphinx`_ (for document generation)
+- `ruff`_ (for code style check)
+
+.. _`Python 3.12.x`: https://www.python.org/
+.. _`NumPy`: https://numpy.org/
+.. _`SciPy`: https://scipy.org/
+.. _`Matplotlib`: https://matplotlib.org/
+.. _`cvxpy`: https://www.cvxpy.org/
+.. _`pytest`: https://docs.pytest.org/en/latest/
+.. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist
+.. _`mypy`: https://mypy-lang.org/
+.. _`Sphinx`: https://www.sphinx-doc.org/en/master/index.html
+.. _`ruff`: https://github.com/astral-sh/ruff
+
+For instructions on installing the above libraries, please refer to
+this section ":ref:`How to run sample codes`".
+
+Audio overview of this project
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+For an audio overview of this project, please refer to this `YouTube video`_.
+
+.. _`YouTube video`: https://www.youtube.com/watch?v=uMeRnNoJAfU
+
+Arxiv paper
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+We have published a paper on this project on Arxiv in 2018.
+
+See this paper for more details about this Project:
+
+- `PythonRobotics: a Python code collection of robotics algorithms`_ (`BibTeX`_)
+
+.. _`PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703
+.. _`BibTeX`: https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib
+
diff --git a/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst
new file mode 100644
index 0000000000..b92fc9bde0
--- /dev/null
+++ b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst
@@ -0,0 +1,118 @@
+.. _`How to run sample codes`:
+
+How to run sample codes
+-------------------------
+
+In this chapter, we will explain the setup process for running each sample code
+in PythonRobotics and describe the contents of each directory.
+
+Steps to setup and run sample codes
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+1. Install `Python 3.12.x`_
+
+Note that older versions of Python3 might work, but we recommend using
+the specified version, because the sample codes are only tested with it.
+
+2. If you prefer to use conda for package management, install
+Anaconda or Miniconda to use `conda`_ command.
+
+3. Clone this repo and go into dir.
+
+.. code-block::
+
+ >$ git clone https://github.com/AtsushiSakai/PythonRobotics.git
+
+ >$ cd PythonRobotics
+
+
+4. Install the required libraries.
+
+We have prepared requirements management files for `conda`_ and `pip`_ under
+the requirements directory. Using these files makes it easy to install the necessary libraries.
+
+using conda :
+
+.. code-block::
+
+ >$ conda env create -f requirements/environment.yml
+
+using pip :
+
+.. code-block::
+
+ >$ pip install -r requirements/requirements.txt
+
+
+5. Execute python script in each directory.
+
+For example, to run the sample code of `Extented Kalman Filter` in the
+`localization` directory, execute the following command:
+
+.. code-block::
+
+ >$ cd localization/extended_kalman_filter
+
+ >$ python extended_kalman_filter.py
+
+Then, you can see this animation of the EKF algorithm based localization:
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif
+
+Please refer to the `Directory structure`_ section for more details on the contents of each directory.
+
+6. Add star to this repo if you like it 😃.
+
+.. _`Python 3.12.x`: https://www.python.org/
+.. _`conda`: https://docs.conda.io/projects/conda/en/stable/user-guide/install/index.html
+.. _`pip`: https://pip.pypa.io/en/stable/
+.. _`the requirements directory`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/requirements
+
+.. _`Directory structure`:
+
+Directory structure
+~~~~~~~~~~~~~~~~~~~~
+
+The top-level directory structure of PythonRobotics is as follows:
+
+Sample codes directories:
+
+- `AerialNavigation`_ : the sample codes of aerial navigation algorithms for drones and rocket landing.
+- `ArmNavigation`_ : the sample codes of arm navigation algorithms for robotic arms.
+- `Localization`_ : the sample codes of localization algorithms.
+- `Bipedal`_ : the sample codes of bipedal walking algorithms for legged robots.
+- `Control`_ : the sample codes of control algorithms for robotic systems.
+- `Mapping`_ : the sample codes of mapping or obstacle shape recognition algorithms.
+- `PathPlanning`_ : the sample codes of path planning algorithms.
+- `PathTracking`_ : the sample codes of path tracking algorithms for car like robots.
+- `SLAM`_ : the sample codes of SLAM algorithms.
+
+Other directories:
+
+- `docs`_ : This directory contains the documentation of PythonRobotics.
+- `requirements`_ : This directory contains the requirements management files.
+- `tests`_ : This directory contains the unit test files.
+- `utils`_ : This directory contains utility functions used in some sample codes in common.
+- `.github`_ : This directory contains the GitHub Actions configuration files.
+- `.circleci`_ : This directory contains the CircleCI configuration files.
+
+The structure of this document is the same as that of the sample code
+directories mentioned above.
+For more details, please refer to the :ref:`How to read this textbook` section.
+
+
+.. _`AerialNavigation`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/AerialNavigation
+.. _`ArmNavigation`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/ArmNavigation
+.. _`Localization`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Localization
+.. _`Bipedal`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Bipedal
+.. _`Control`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Control
+.. _`Mapping`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Mapping
+.. _`PathPlanning`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/PathPlanning
+.. _`PathTracking`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/PathTracking
+.. _`SLAM`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM
+.. _`docs`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs
+.. _`requirements`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/requirements
+.. _`tests`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/tests
+.. _`utils`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/utils
+.. _`.github`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/.github
+.. _`.circleci`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/.circleci
diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst
new file mode 100644
index 0000000000..9e773e930c
--- /dev/null
+++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst
@@ -0,0 +1,227 @@
+How to contribute
+=================
+
+This document describes how to contribute this project.
+There are several ways to contribute to this project as below:
+
+#. `Adding a new algorithm example`_
+#. `Reporting and fixing a defect`_
+#. `Adding missed documentations for existing examples`_
+#. `Supporting this project`_
+
+Before contributing
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Please check following items before contributing:
+
+Understanding this project
+---------------------------
+
+Please check this :ref:`What is PythonRobotics?` section and this paper
+`PythonRobotics: a Python code collection of robotics algorithms`_
+to understand the philosophies of this project.
+
+.. _`PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703
+
+Check your Python version.
+---------------------------
+
+We only accept a PR for Python 3.13.x or higher.
+
+We will not accept a PR for Python 2.x.
+
+.. _`Adding a new algorithm example`:
+
+1. Adding a new algorithm example
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+This is a step by step manual to add a new algorithm example.
+
+Step 1: Choose an algorithm to implement
+-----------------------------------------
+
+Before choosing an algorithm, please check the :ref:`getting started` doc to
+understand this project's philosophy and setup your development environment.
+
+If an algorithm is widely used and successful, let's create an issue to
+propose it for our community.
+
+If some people agree by thumbs up or posting positive comments, let go to next step.
+
+It is OK to just create an issue to propose adding an algorithm, someone might implement it.
+
+In that case, please share any papers or documentations to implement it.
+
+
+Step 2: Implement the algorithm with matplotlib based animation
+----------------------------------------------------------------
+
+When you implement an algorithm, please keep the following items in mind.
+
+1. Use only Python. Other language code is not acceptable.
+
+2. This project only accept codes for python 3.9 or higher.
+
+3. Use matplotlib based animation to show how the algorithm works.
+
+4. Only use current :ref:`Requirements` libraries, not adding new dependencies.
+
+5. Keep simple your code. The main goal is to make it easy for users to understand the algorithm, not for practical usage.
+
+
+Step 3: Add a unittest
+----------------------
+If you add a new algorithm sample code, please add a unit test file under `tests dir`_.
+
+This sample test code might help you : `test_a_star.py`_.
+
+At the least, try to run the example code without animation in the unit test.
+
+If you want to run the test suites locally, you can use the `runtests.sh` script by just executing it.
+
+The `test_codestyle.py`_ check code style for your PR's codes.
+
+
+.. _`how to write doc`:
+
+Step 4: Write a document about the algorithm
+----------------------------------------------
+Please add a document to describe the algorithm details, mathematical backgrounds and show graphs and animation gif.
+
+This project is using `Sphinx`_ as a document builder, all documentations are written by `reStructuredText`_.
+
+You can add a new rst file under the subdirectory in `doc modules dir`_ and the top rst file can include it.
+
+Please check other documents for details.
+
+You can build the doc locally based on `doc README`_.
+
+For creating a gif animation, you can use this tool: `matplotrecorder`_.
+
+The created gif file should be stored in the `PythonRoboticsGifs`_ repository,
+so please create a PR to add it and refer to it in the doc.
+
+Note that the `reStructuredText`_ based doc should only focus on the
+mathematics and the algorithm of the example.
+
+Documentations related codes should be in the python script as the header
+comments of the script or docstrings of each function.
+
+Also, each document should have a link to the code in Github.
+You can easily add the link by using the `.. autoclass::`, `.. autofunction::`, and `.. automodule` by Sphinx's `autodoc`_ module.
+
+Using this `autodoc`_ module, the generated documentations have the link to the code in Github like:
+
+.. image:: /_static/img/source_link_1.png
+
+When you click the link, you will jump to the source code in Github like:
+
+.. image:: /_static/img/source_link_2.png
+
+
+
+.. _`submit a pull request`:
+
+Step 5: Submit a pull request and fix codes based on review
+------------------------------------------------------------
+
+Let's submit a pull request when your code, test, and doc are ready.
+
+At first, please fix all CI errors before code review.
+
+You can check your PR doc from the CI panel.
+
+After the "ci/circleci: build_doc" CI is succeeded,
+you can access you PR doc with clicking the [Details] of the "ci/circleci: build_doc artifact" CI.
+
+.. image:: /_static/img/doc_ci.png
+
+After that, I will start the review.
+
+Note that this is my hobby project; I appreciate your patience during the review process.
+
+
+
+.. _`Reporting and fixing a defect`:
+
+2. Reporting and fixing a defect
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Reporting and fixing a defect is also great contribution.
+
+When you report an issue, please provide these information:
+
+- A clear and concise description of what the bug is.
+- A clear and concise description of what you expected to happen.
+- Screenshots to help explain your problem if applicable.
+- OS version
+- Python version
+- Each library versions
+
+If you want to fix any bug, you can find reported issues in `bug labeled issues`_.
+
+If you fix a bug of existing codes, please add a test function
+in the test code to show the issue was solved.
+
+This doc `submit a pull request`_ can be helpful to submit a pull request.
+
+
+.. _`Adding missed documentations for existing examples`:
+
+3. Adding missed documentations for existing examples
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Adding the missed documentations for existing examples is also great contribution.
+
+If you check the `Python Robotics Docs`_, you can notice that some of the examples
+only have a simulation gif or short overview descriptions or just TBD.,
+but no detailed algorithm or mathematical description.
+These documents need to be improved.
+
+This doc `how to write doc`_ can be helpful to write documents.
+
+.. _`Supporting this project`:
+
+4. Supporting this project
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Supporting this project financially is also a great contribution!!.
+
+If you or your company would like to support this project, please consider:
+
+- `Sponsor @AtsushiSakai on GitHub Sponsors`_
+
+- `Become a backer or sponsor on Patreon`_
+
+- `One-time donation via PayPal`_
+
+If you would like to support us in some other way, please contact with creating an issue.
+
+Current Major Sponsors:
+
+#. `GitHub`_ : They are providing a GitHub Copilot Pro license for this OSS development.
+#. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development.
+#. `1Password`_ : They are providing a free license of their 1Password team license for this OSS project.
+
+
+
+.. _`Python Robotics Docs`: https://atsushisakai.github.io/PythonRobotics
+.. _`bug labeled issues`: https://github.com/AtsushiSakai/PythonRobotics/issues?q=is%3Aissue+is%3Aopen+label%3Abug
+.. _`tests dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/tests
+.. _`test_a_star.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_a_star.py
+.. _`Sphinx`: https://www.sphinx-doc.org/
+.. _`reStructuredText`: https://www.sphinx-doc.org/en/master/usage/restructuredtext/basics.html
+.. _`doc modules dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs/modules
+.. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md
+.. _`test_codestyle.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_codestyle.py
+.. _`JetBrains`: https://www.jetbrains.com/
+.. _`GitHub`: https://www.github.com/
+.. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai
+.. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma
+.. _`One-time donation via PayPal`: https://www.paypal.com/paypalme/myenigmapay/
+.. _`1Password`: https://github.com/1Password/for-open-source
+.. _`matplotrecorder`: https://github.com/AtsushiSakai/matplotrecorder
+.. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs
+.. _`autodoc`: https://www.sphinx-doc.org/en/master/usage/extensions/autodoc.html
+
+
diff --git a/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst
new file mode 100644
index 0000000000..1625c838af
--- /dev/null
+++ b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst
@@ -0,0 +1,14 @@
+.. _`How to read this textbook`:
+
+How to read this textbook
+--------------------------
+
+This document is structured to help you learn the fundamental concepts
+behind each sample code in PythonRobotics.
+
+If you already have some knowledge of robotics technologies, you can start
+by reading any document that interests you.
+
+However, if you have no prior knowledge of robotics technologies, it is
+recommended that you first read the :ref:`Introduction` section and then proceed
+to the documents related to the technical fields that interest you.
\ No newline at end of file
diff --git a/docs/modules/10_inverted_pendulum/inverted-pendulum.png b/docs/modules/10_inverted_pendulum/inverted-pendulum.png
new file mode 100644
index 0000000000..841aed9220
Binary files /dev/null and b/docs/modules/10_inverted_pendulum/inverted-pendulum.png differ
diff --git a/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst
new file mode 100644
index 0000000000..58dc0f2e57
--- /dev/null
+++ b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst
@@ -0,0 +1,115 @@
+.. _`Inverted Pendulum`:
+
+Inverted Pendulum
+------------------
+
+An inverted pendulum on a cart consists of a mass :math:`m` at the top of a pole of length :math:`l` pivoted on a
+horizontally moving base as shown in the adjacent.
+
+The objective of the control system is to balance the inverted pendulum by applying a force to the cart that the pendulum is attached to.
+
+Modeling
+~~~~~~~~~~~~
+
+.. image:: inverted-pendulum.png
+ :align: center
+
+- :math:`M`: mass of the cart
+- :math:`m`: mass of the load on the top of the rod
+- :math:`l`: length of the rod
+- :math:`u`: force applied to the cart
+- :math:`x`: cart position coordinate
+- :math:`\theta`: pendulum angle from vertical
+
+Using Lagrange's equations:
+
+.. math::
+ & (M + m)\ddot{x} - ml\ddot{\theta}cos{\theta} + ml\dot{\theta^2}\sin{\theta} = u \\
+ & l\ddot{\theta} - g\sin{\theta} = \ddot{x}\cos{\theta}
+
+See this `link `__ for more details.
+
+So
+
+.. math::
+ & \ddot{x} = \frac{m(gcos{\theta} - \dot{\theta}^2l)sin{\theta} + u}{M + m - mcos^2{\theta}} \\
+ & \ddot{\theta} = \frac{g(M + m)sin{\theta} - \dot{\theta}^2lmsin{\theta}cos{\theta} + ucos{\theta}}{l(M + m - mcos^2{\theta})}
+
+
+Linearized model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`.
+
+.. math::
+ & \ddot{x} = \frac{gm}{M}\theta + \frac{1}{M}u\\
+ & \ddot{\theta} = \frac{g(M + m)}{Ml}\theta + \frac{1}{Ml}u
+
+State space:
+
+.. math::
+ & \dot{x} = Ax + Bu \\
+ & y = Cx + Du
+
+where
+
+.. math::
+ & x = [x, \dot{x}, \theta,\dot{\theta}]\\
+ & A = \begin{bmatrix} 0 & 1 & 0 & 0\\0 & 0 & \frac{gm}{M} & 0\\0 & 0 & 0 & 1\\0 & 0 & \frac{g(M + m)}{Ml} & 0 \end{bmatrix}\\
+ & B = \begin{bmatrix} 0 \\ \frac{1}{M} \\ 0 \\ \frac{1}{Ml} \end{bmatrix}
+
+If control only \theta
+
+.. math::
+ & C = \begin{bmatrix} 0 & 0 & 1 & 0 \end{bmatrix}\\
+ & D = [0]
+
+If control x and \theta
+
+.. math::
+ & C = \begin{bmatrix} 1 & 0 & 0 & 0\\0 & 0 & 1 & 0 \end{bmatrix}\\
+ & D = \begin{bmatrix} 0 \\ 0 \end{bmatrix}
+
+LQR control
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The LQR controller minimize this cost function defined as:
+
+.. math:: J = x^T Q x + u^T R u
+
+the feedback control law that minimizes the value of the cost is:
+
+.. math:: u = -K x
+
+where:
+
+.. math:: K = (B^T P B + R)^{-1} B^T P A
+
+and :math:`P` is the unique positive definite solution to the discrete time
+`algebraic Riccati equation `__ (DARE):
+
+.. math:: P = A^T P A - A^T P B ( R + B^T P B )^{-1} B^T P A + Q
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation_lqr.gif
+
+Code Link
+^^^^^^^^^^^
+
+.. autofunction:: InvertedPendulum.inverted_pendulum_lqr_control.main
+
+
+MPC control
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+The MPC controller minimize this cost function defined as:
+
+.. math:: J = x^T Q x + u^T R u
+
+subject to:
+
+- Linearized Inverted Pendulum model
+- Initial state
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif
+
+Code Link
+^^^^^^^^^^^
+
+.. autofunction:: InvertedPendulum.inverted_pendulum_mpc_control.main
+
diff --git a/docs/modules/11_utils/plot/curvature_plot.png b/docs/modules/11_utils/plot/curvature_plot.png
new file mode 100644
index 0000000000..891d300829
Binary files /dev/null and b/docs/modules/11_utils/plot/curvature_plot.png differ
diff --git a/docs/modules/11_utils/plot/plot_main.rst b/docs/modules/11_utils/plot/plot_main.rst
new file mode 100644
index 0000000000..b5fef0c4a1
--- /dev/null
+++ b/docs/modules/11_utils/plot/plot_main.rst
@@ -0,0 +1,16 @@
+.. _plot_utils:
+
+Plotting Utilities
+-------------------
+
+This module contains a number of utility functions for plotting data.
+
+.. _plot_curvature:
+
+plot_curvature
+~~~~~~~~~~~~~~~
+
+.. autofunction:: utils.plot.plot_curvature
+
+.. image:: curvature_plot.png
+
diff --git a/docs/modules/11_utils/utils_main.rst b/docs/modules/11_utils/utils_main.rst
new file mode 100644
index 0000000000..95c982b077
--- /dev/null
+++ b/docs/modules/11_utils/utils_main.rst
@@ -0,0 +1,12 @@
+.. _`utils`:
+
+Utilities
+==========
+
+Common utilities for PythonRobotics.
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ plot/plot
diff --git a/docs/modules/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png
diff --git a/docs/modules/Kalmanfilter_basics_2.rst b/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst
similarity index 99%
rename from docs/modules/Kalmanfilter_basics_2.rst
rename to docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst
index 9ae6fc5bcb..b7ff84e6f6 100644
--- a/docs/modules/Kalmanfilter_basics_2.rst
+++ b/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst
@@ -331,7 +331,7 @@ are vectors and matrices, but the concepts are exactly the same:
- Use the process model to predict the next state (the prior)
- Form an estimate part way between the measurement and the prior
-References:
+Reference
~~~~~~~~~~~
1. Roger Labbe’s
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png
diff --git a/docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png
similarity index 100%
rename from docs/modules/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png
rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png
diff --git a/docs/modules/Kalmanfilter_basics.rst b/docs/modules/12_appendix/Kalmanfilter_basics_main.rst
similarity index 98%
rename from docs/modules/Kalmanfilter_basics.rst
rename to docs/modules/12_appendix/Kalmanfilter_basics_main.rst
index ce84fe0db4..a1d99d47ef 100644
--- a/docs/modules/Kalmanfilter_basics.rst
+++ b/docs/modules/12_appendix/Kalmanfilter_basics_main.rst
@@ -180,7 +180,7 @@ Central Limit Theorem
^^^^^^^^^^^^^^^^^^^^^
According to this theorem, the average of n samples of random and
-independant variables tends to follow a normal distribution as we
+independent variables tends to follow a normal distribution as we
increase the sample size.(Generally, for n>=30)
.. code-block:: ipython3
@@ -222,9 +222,8 @@ described with two parameters, the mean (:math:`\mu`) and the variance
f(x, \mu, \sigma) = \frac{1}{\sigma\sqrt{2\pi}} \exp\big [{-\frac{(x-\mu)^2}{2\sigma^2} }\big ]
- Range is
-.. math:: [-\inf,\inf]
+Range is :math:`[-\inf,\inf]`
This is just a function of mean(\ :math:`\mu`) and standard deviation
(:math:`\sigma`) and what gives the normal distribution the
@@ -279,7 +278,8 @@ New mean is
.. math:: \mu_\mathtt{new} = \frac{\sigma_z^2\bar\mu + \bar\sigma^2z}{\bar\sigma^2+\sigma_z^2}
- New variance is
+
+New variance is
.. math::
@@ -336,7 +336,7 @@ of the two.
.. math::
\begin{gathered}\mu_x = \mu_p + \mu_z \\
- \sigma_x^2 = \sigma_z^2+\sigma_p^2\, \square\end{gathered}
+ \sigma_x^2 = \sigma_z^2+\sigma_p^2\, \end{gathered}
.. code-block:: ipython3
@@ -552,7 +552,7 @@ a given (X,Y) value.
.. image:: Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png
-References:
+Reference
~~~~~~~~~~~
1. Roger Labbe’s
diff --git a/docs/modules/12_appendix/appendix_main.rst b/docs/modules/12_appendix/appendix_main.rst
new file mode 100644
index 0000000000..d0b9eeea3a
--- /dev/null
+++ b/docs/modules/12_appendix/appendix_main.rst
@@ -0,0 +1,15 @@
+.. _`Appendix`:
+
+Appendix
+==============
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ steering_motion_model
+ Kalmanfilter_basics
+ Kalmanfilter_basics_2
+ internal_sensors
+ external_sensors
+
diff --git a/docs/modules/12_appendix/external_sensors_main.rst b/docs/modules/12_appendix/external_sensors_main.rst
new file mode 100644
index 0000000000..b7caaf2c3a
--- /dev/null
+++ b/docs/modules/12_appendix/external_sensors_main.rst
@@ -0,0 +1,65 @@
+.. _`External Sensors for Robots`:
+
+External Sensors for Robots
+============================
+
+This project, `PythonRobotics`, focuses on algorithms, so hardware is not included.
+However, having basic knowledge of hardware in robotics is also important for understanding algorithms.
+Therefore, we will provide an overview.
+
+Introduction
+------------
+
+In recent years, the application of robotic technology has advanced, particularly in areas such as autonomous vehicles and disaster response robots. A crucial element in these technologies is external recognition—the robot's ability to understand its surrounding environment, identify safe zones, and detect moving objects using onboard sensors. Achieving effective external recognition involves various techniques, but equally important is the selection of appropriate sensors. Robots, like the sensors they employ, come in many forms, but external recognition sensors can be broadly categorized into three types. Developing an advanced external recognition system requires a thorough understanding of each sensor's principles and characteristics to determine their optimal application. This article summarizes the principles and features of these sensors for personal study purposes.
+
+Laser Sensors
+-------------
+
+Laser sensors measure distances by utilizing light, commonly referred to as Light Detection and Ranging (LIDAR). They operate by emitting light towards an object and calculating the distance based on the time it takes for the reflected light to return, using the speed of light as a constant.
+
+Radar Sensors
+-------------
+
+Radar measures distances using radio waves, commonly referred to as Radio Detection and Ranging (RADAR). It operates by transmitting radio signals towards an object and calculating the distance based on the time it takes for the reflected waves to return, using the speed of radio waves as a constant.
+
+
+Monocular Cameras
+-----------------
+
+Monocular cameras utilize a single camera to recognize the external environment. Compared to other sensors, they can detect color and brightness information, making them primarily useful for object recognition. However, they face challenges in independently measuring distances to surrounding objects and may struggle in low-light or dark conditions.
+
+Requirements for Cameras and Image Processing in Robotics
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+While camera sensors are widely used in applications like surveillance, deploying them in robotics necessitates meeting specific requirements:
+
+1. High dynamic range to adapt to various lighting conditions
+2. Wide measurement range
+3. Capability for three-dimensional measurement through techniques like motion stereo
+4. Real-time processing with high frame rates
+5. Cost-effectiveness
+
+Stereo Cameras
+--------------
+
+Stereo cameras employ multiple cameras to measure distances to surrounding objects. By knowing the positions and orientations of each camera and analyzing the disparity in the images (parallax), the distance to a specific point (the object represented by a particular pixel) can be calculated.
+
+Characteristics of Stereo Cameras
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Advantages of stereo cameras include the ability to obtain high-precision and high-density distance information at close range, depending on factors like camera resolution and the distance between cameras (baseline). This makes them suitable for indoor robots that require precise shape recognition of nearby objects. Additionally, stereo cameras are relatively cost-effective compared to other sensors, leading to their use in consumer products like Subaru's EyeSight system. However, stereo cameras are less effective for long-distance measurements due to a decrease in accuracy proportional to the square of the distance. They are also susceptible to environmental factors such as lighting conditions.
+
+Ultrasonic Sensors
+------------------
+
+Ultrasonic sensors are commonly used in indoor robots and some automotive autonomous driving systems. Their features include affordability compared to laser or radar sensors, the ability to detect very close objects, and the capability to sense materials like glass, which may be challenging for lasers or cameras. However, they have limitations such as shorter maximum measurement distances and lower resolution and accuracy.
+
+References
+----------
+
+- Wikipedia articles:
+
+ - `Lidar Sensors `_
+ - `Radar Sensors `_
+ - `Stereo Cameras `_
+ - `Ultrasonic Sensors `_
\ No newline at end of file
diff --git a/docs/modules/12_appendix/internal_sensors_main.rst b/docs/modules/12_appendix/internal_sensors_main.rst
new file mode 100644
index 0000000000..fa2594a2bf
--- /dev/null
+++ b/docs/modules/12_appendix/internal_sensors_main.rst
@@ -0,0 +1,61 @@
+.. _`Internal Sensors for Robots`:
+
+Internal Sensors for Robots
+============================
+
+This project, `PythonRobotics`, focuses on algorithms, so hardware is not included. However, having basic knowledge of hardware in robotics is also important for understanding algorithms. Therefore, we will provide an overview.
+
+Introduction
+-------------
+
+In robotic systems, internal sensors play a crucial role in monitoring the robot’s internal state, such as orientation, acceleration, angular velocity, altitude, and temperature. These sensors provide essential feedback that supports control, localization, and safety mechanisms. While external sensors perceive the environment, internal sensors give the robot self-awareness of its own motion and condition. Understanding the principles and characteristics of these sensors is vital to fully utilize their information within algorithms and decision-making systems. This section outlines the main internal sensors used in robotics.
+
+Global Navigation Satellite System (GNSS)
+-----------------------------------------
+
+GNSS is a satellite-based navigation system that provides global positioning and time information by analyzing signals from multiple satellites. It is commonly used in outdoor environments for absolute positioning. Although GNSS offers global coverage without infrastructure dependency, its performance is limited indoors or in obstructed areas, and it suffers from low update rates and susceptibility to signal noise. It is widely used in outdoor navigation for drones, vehicles, and delivery robots.
+
+Gyroscope
+----------
+
+A gyroscope measures angular velocity around the robot’s axes, enabling orientation and attitude estimation through detection of the Coriolis effect. Gyroscopes are compact, cost-effective, and provide high update rates, but they are prone to drift and require calibration or sensor fusion for long-term accuracy. These sensors are essential in drones, balancing robots, and IMU-based systems for motion tracking.
+
+Accelerometer
+---------------
+
+An accelerometer measures linear acceleration along one or more axes, typically by detecting mass displacement due to motion. It is small, affordable, and useful for detecting movement, tilt, or vibration. However, accelerometers are limited by noisy output and cannot independently determine position without integration and fusion. They are commonly applied in wearable robotics, step counters, and vibration sensing.
+
+Magnetometer
+--------------
+
+A magnetometer measures the direction and intensity of magnetic fields, enabling heading estimation based on Earth’s magnetic field. It is lightweight and useful for orientation, especially in GPS-denied environments, though it is sensitive to interference from electronics and requires calibration. Magnetometers are often used in conjunction with IMUs for navigation and directional awareness.
+
+Inertial Measurement Unit (IMU)
+--------------------------------
+
+An IMU integrates a gyroscope, accelerometer, and sometimes a magnetometer to estimate a robot's motion and orientation through sensor fusion techniques such as Kalman filters. IMUs are compact and provide high-frequency data, which is essential for localization and navigation in GPS-denied areas. Nonetheless, they accumulate drift over time and require complex filtering to maintain accuracy. IMUs are found in drones, mobile robots, and motion tracking systems.
+
+Pressure Sensor
+----------------
+
+Pressure sensors detect atmospheric or fluid pressure by measuring the force exerted on a diaphragm. They are effective for estimating altitude and monitoring environmental conditions, especially in drones and underwater robots. Although cost-effective and efficient, their accuracy may degrade due to temperature variation and limitations in low-altitude resolution.
+
+Temperature Sensor
+--------------------
+
+Temperature sensors monitor environmental or internal component temperatures, using changes in resistance or voltage depending on sensor type (e.g., RTD or thermocouple). They are simple and reliable for safety and thermal regulation, though they may respond slowly and be affected by nearby electronics. Common applications include battery and motor monitoring, safety systems, and ambient sensing.
+
+References
+----------
+
+- *Introduction to Autonomous Mobile Robots*, Roland Siegwart, Illah Nourbakhsh, Davide Scaramuzza
+- *Probabilistic Robotics*, Sebastian Thrun, Wolfram Burgard, Dieter Fox
+- Wikipedia articles:
+
+ - `Inertial Measurement Unit (IMU) `_
+ - `Accelerometer `_
+ - `Gyroscope `_
+ - `Magnetometer `_
+ - `Pressure sensor `_
+ - `Temperature sensor `_
+- `Adafruit Sensor Guides `_
\ No newline at end of file
diff --git a/docs/modules/12_appendix/steering_motion_model/steering_model.png b/docs/modules/12_appendix/steering_motion_model/steering_model.png
new file mode 100644
index 0000000000..c66dded87a
Binary files /dev/null and b/docs/modules/12_appendix/steering_motion_model/steering_model.png differ
diff --git a/docs/modules/12_appendix/steering_motion_model/turning_radius_calc1.png b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc1.png
new file mode 100644
index 0000000000..3de7ed8797
Binary files /dev/null and b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc1.png differ
diff --git a/docs/modules/12_appendix/steering_motion_model/turning_radius_calc2.png b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc2.png
new file mode 100644
index 0000000000..f7e776bf40
Binary files /dev/null and b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc2.png differ
diff --git a/docs/modules/12_appendix/steering_motion_model_main.rst b/docs/modules/12_appendix/steering_motion_model_main.rst
new file mode 100644
index 0000000000..c697123fa2
--- /dev/null
+++ b/docs/modules/12_appendix/steering_motion_model_main.rst
@@ -0,0 +1,97 @@
+
+Steering Motion Model
+-----------------------
+
+Turning radius calculation by steering motion model
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The turning Radius represents the radius of the circle when the robot turns, as shown in the diagram below.
+
+.. image:: steering_motion_model/steering_model.png
+
+When the steering angle is tilted by :math:`\delta`,
+the turning radius :math:`R` can be calculated using the following equation,
+based on the geometric relationship between the wheelbase (WB),
+which is the distance between the rear wheel center and the front wheel center,
+and the assumption that the turning radius circle passes through the center of
+the rear wheels in the diagram above.
+
+:math:`R = \frac{WB}{tan\delta}`
+
+The curvature :math:`\kappa` is the reciprocal of the turning radius:
+
+:math:`\kappa = \frac{tan\delta}{WB}`
+
+In the diagram above, the angular difference :math:`\Delta \theta` in the vehicle’s heading between two points on the turning radius :math:`R`
+is the same as the angle of the vector connecting the two points from the center of the turn.
+
+From the formula for the length of an arc and the radius,
+
+:math:`\Delta \theta = \frac{s}{R}`
+
+Here, :math:`s` is the distance between two points on the turning radius.
+
+So, yaw rate :math:`\omega` can be calculated as follows.
+
+:math:`\omega = \frac{v}{R}`
+
+and
+
+:math:`\omega = v\kappa`
+
+here, :math:`v` is the velocity of the vehicle.
+
+
+Turning radius calculation by 2 consecutive positions of the robot trajectory
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+In this section, we will derive the formula for the turning radius from 2 consecutive positions of the robot trajectory.
+
+.. image:: steering_motion_model/turning_radius_calc1.png
+
+As shown in the upper diagram above, the robot moves from a point at time :math:`t` to a point at time :math:`t+1`.
+Each point is represented by a 2D position :math:`(x_t, y_t)` and an orientation :math:`\theta_t`.
+
+The distance between the two points is :math:`d = \sqrt{(x_{t+1} - x_t)^2 + (y_{t+1} - y_t)^2}`.
+
+The angle between the two vectors from the turning center to the two points is :math:`\theta = \theta_{t+1} - \theta_t`.
+Here, by drawing a perpendicular line from the center of the turning radius
+to a straight line of length :math:`d` connecting two points,
+the following equation can be derived from the resulting right triangle.
+
+:math:`sin\frac{\theta}{2} = \frac{d}{2R}`
+
+So, the turning radius :math:`R` can be calculated as follows.
+
+:math:`R = \frac{d}{2sin\frac{\theta}{2}}`
+
+The curvature :math:`\kappa` is the reciprocal of the turning radius.
+So, the curvature can be calculated as follows.
+
+:math:`\kappa = \frac{2sin\frac{\theta}{2}}{d}`
+
+Target speed by maximum steering speed
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+If the maximum steering speed is given as :math:`\dot{\delta}_{max}`,
+the maximum curvature change rate :math:`\dot{\kappa}_{max}` can be calculated as follows:
+
+:math:`\dot{\kappa}_{max} = \frac{tan\dot{\delta}_{max}}{WB}`
+
+From the curvature calculation by 2 consecutive positions of the robot trajectory,
+
+the maximum curvature change rate :math:`\dot{\kappa}_{max}` can be calculated as follows:
+
+:math:`\dot{\kappa}_{max} = \frac{\kappa_{t+1}-\kappa_{t}}{\Delta t}`
+
+If we can assume that the vehicle will not exceed the maximum curvature change rate,
+
+the target minimum velocity :math:`v_{min}` can be calculated as follows:
+
+:math:`v_{min} = \frac{d_{t+1}+d_{t}}{\Delta t} = \frac{d_{t+1}+d_{t}}{(\kappa_{t+1}-\kappa_{t})}\frac{tan\dot{\delta}_{max}}{WB}`
+
+
+Reference
+~~~~~~~~~~~
+
+- `Vehicle Dynamics and Control `_
diff --git a/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst
new file mode 100644
index 0000000000..22849f7c54
--- /dev/null
+++ b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst
@@ -0,0 +1,104 @@
+Behavior Tree
+-------------
+
+Behavior Tree is a modular, hierarchical decision model that is widely used in robot control, and game development.
+It present some similarities to hierarchical state machines with the key difference that the main building block of a behavior is a task rather than a state.
+Behavior Tree have been shown to generalize several other control architectures (https://ieeexplore.ieee.org/document/7790863)
+
+Code Link
+~~~~~~~~~~~~~
+
+Control Node
+++++++++++++
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ControlNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SequenceNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SelectorNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.WhileDoElseNode
+
+Action Node
+++++++++++++
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ActionNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.EchoNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SleepNode
+
+Decorator Node
+++++++++++++++
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.DecoratorNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.InverterNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.TimeoutNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.DelayNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ForceSuccessNode
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ForceFailureNode
+
+Behavior Tree Factory
++++++++++++++++++++++
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.BehaviorTreeFactory
+ :members:
+
+Behavior Tree
++++++++++++++
+
+.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.BehaviorTree
+ :members:
+
+Example
+~~~~~~~
+
+Visualize the behavior tree by `xml-tree-visual `_.
+
+.. image:: ./robot_behavior_case.svg
+
+Print the behavior tree
+
+.. code-block:: text
+
+ Behavior Tree
+ [Robot Main Controller]
+ [Battery Management]
+ (Low Battery Detection)
+
+
+
+ [Patrol Task]
+
+ [Move to Position A]
+
+ [Obstacle Handling A]
+ [Obstacle Present]
+
+
+
+
+ [Move to Position B]
+ (Short Wait)
+
+
+ (Limited Time Obstacle Handling)
+ [Obstacle Present]
+
+
+
+ [Conditional Move to C]
+
+ [Perform Position C Task]
+
+ (Ensure Completion)
+
+
+
+
+ Behavior Tree
diff --git a/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg b/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg
new file mode 100644
index 0000000000..a3d43aed52
--- /dev/null
+++ b/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg
@@ -0,0 +1,22 @@
+Selector name: Robot Main Controller Sequence name: Battery Management Sequence name: Patrol Task Inverter name: Low Battery Detection Echo name: Low Battery Warning message: Battery level low! Charging needed ChargeBattery name: Charge Battery charge_rate: 20 Echo name: Start Task message: Starting patrol task Sequence name: Move to Position A Sequence name: Move to Position B WhileDoElse name: Conditional Move to C Echo name: Complete Patrol message: Patrol task completed, returning to charging station MoveToPosition name: Return to Charging Station position: Charging Station move_duration: 4 CheckBattery name: Check Battery threshold: 30 MoveToPosition name: Move to A position: A move_duration: 2 Selector name: Obstacle Handling A PerformTask name: Position A Task task_name: Check Device Status task_duration: 2 Delay name: Short Wait sec: 1 MoveToPosition name: Move to B position: B move_duration: 3 Timeout name: Limited Time Obstacle Handling sec: 2 PerformTask name: Position B Task task_name: Data Collection task_duration: 2.5 CheckBattery name: Check Sufficient Battery threshold: 50 Sequence name: Perform Position C Task Echo name: Skip Position C message: Insufficient power, skipping position C task Sequence name: Obstacle Present Echo name: No Obstacle message: Path clear Echo name: Prepare Movement message: Preparing to move to next position Sequence name: Obstacle Present MoveToPosition name: Move to C position: C move_duration: 2.5 ForceSuccess name: Ensure Completion DetectObstacle name: Detect Obstacle obstacle_probability: 0.3 AvoidObstacle name: Avoid Obstacle avoid_duration: 1.5 DetectObstacle name: Detect Obstacle obstacle_probability: 0.4 AvoidObstacle name: Avoid Obstacle avoid_duration: 1.8 PerformTask name: Position C Task task_name: Environment Monitoring task_duration: 2
\ No newline at end of file
diff --git a/docs/modules/13_mission_planning/mission_planning_main.rst b/docs/modules/13_mission_planning/mission_planning_main.rst
new file mode 100644
index 0000000000..c35eacd8d5
--- /dev/null
+++ b/docs/modules/13_mission_planning/mission_planning_main.rst
@@ -0,0 +1,13 @@
+.. _`Mission Planning`:
+
+Mission Planning
+================
+
+Mission planning includes tools such as finite state machines and behavior trees used to describe robot behavior and high level task planning.
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ state_machine/state_machine
+ behavior_tree/behavior_tree
diff --git a/docs/modules/13_mission_planning/state_machine/robot_behavior_case.png b/docs/modules/13_mission_planning/state_machine/robot_behavior_case.png
new file mode 100644
index 0000000000..fbc1369cbc
Binary files /dev/null and b/docs/modules/13_mission_planning/state_machine/robot_behavior_case.png differ
diff --git a/docs/modules/13_mission_planning/state_machine/state_machine_main.rst b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst
new file mode 100644
index 0000000000..3f516d46a9
--- /dev/null
+++ b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst
@@ -0,0 +1,74 @@
+State Machine
+-------------
+
+A state machine is a model used to describe the transitions of an object between different states. It clearly shows how an object changes state based on events and may trigger corresponding actions.
+
+Core Concepts
+~~~~~~~~~~~~~
+
+- **State**: A distinct mode or condition of the system (e.g. "Idle", "Running"). Managed by State class with optional on_enter/on_exit callbacks
+- **Event**: A trigger signal that may cause state transitions (e.g. "start", "stop")
+- **Transition**: A state change path from source to destination state triggered by an event
+- **Action**: An operation executed during transition (before entering new state)
+- **Guard**: A precondition that must be satisfied to allow transition
+
+Code Link
+~~~~~~~~~~~
+
+.. autoclass:: MissionPlanning.StateMachine.state_machine.StateMachine
+ :members: add_transition, process, register_state
+ :special-members: __init__
+
+PlantUML Support
+~~~~~~~~~~~~~~~~
+
+The ``generate_plantuml()`` method creates diagrams showing:
+
+- Current state (marked with [*] arrow)
+- All possible transitions
+- Guard conditions in [brackets]
+- Actions prefixed with /
+
+Example
+~~~~~~~
+
+state machine diagram:
++++++++++++++++++++++++
+.. image:: robot_behavior_case.png
+
+state transition table:
++++++++++++++++++++++++
+.. list-table:: State Transitions
+ :header-rows: 1
+ :widths: 20 15 20 20 20
+
+ * - Source State
+ - Event
+ - Target State
+ - Guard
+ - Action
+ * - patrolling
+ - detect_task
+ - executing_task
+ -
+ -
+ * - executing_task
+ - task_complete
+ - patrolling
+ -
+ - reset_task
+ * - executing_task
+ - low_battery
+ - returning_to_base
+ - is_battery_low
+ -
+ * - returning_to_base
+ - reach_base
+ - charging
+ -
+ -
+ * - charging
+ - charge_complete
+ - patrolling
+ -
+ -
\ No newline at end of file
diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst
new file mode 100644
index 0000000000..ca595301a6
--- /dev/null
+++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst
@@ -0,0 +1,107 @@
+Definition of Robotics
+----------------------
+
+This section explains the definition, history, key components, and applications of robotics.
+
+What is Robotics?
+^^^^^^^^^^^^^^^^^^
+
+Robot is a machine that can perform tasks automatically or semi-autonomously.
+Robotics is the study of robots.
+
+The word “robot” comes from the Czech word “robota,” which means “forced labor” or “drudgery.”
+It was first used in the 1920 science fiction play `R.U.R.`_ (Rossum’s Universal Robots)
+by the Czech writer `Karel Čapek`_.
+In the play, robots were artificial workers created to serve humans, but they eventually rebelled.
+
+Over time, “robot” came to refer to machines or automated systems that can perform tasks,
+often with some level of intelligence or autonomy.
+
+Currently, 2 millions robots are working in the world, and the number is increasing every year.
+In South Korea, where the adoption of robots is particularly rapid,
+50 robots are operating per 1,000 people.
+
+.. _`R.U.R.`: https://thereader.mitpress.mit.edu/origin-word-robot-rur/
+.. _`Karel Čapek`: https://en.wikipedia.org/wiki/Karel_%C4%8Capek
+
+The History of Robots
+^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+This timeline highlights key milestones in the history of robotics:
+
+Ancient and Early Concepts (Before 1500s)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The idea of **automated machines** has existed for thousands of years.
+Ancient civilizations imagined mechanical beings:
+
+- **Ancient Greece (4th Century BC)** – Greek engineer `Hero of Alexandria`_ designed early **automata** (self-operating machines) powered by water or air.
+- **Chinese and Arabic Automata (9th–13th Century)** – Inventors like `Ismail Al-Jazari`_ created intricate mechanical devices, including water clocks and automated moving peacocks driven by hydropower.
+
+.. _`Hero of Alexandria`: https://en.wikipedia.org/wiki/Hero_of_Alexandria
+.. _`Ismail Al-Jazari`: https://en.wikipedia.org/wiki/Ismail_al-Jazari
+
+The Birth of Modern Robotics (1500s–1800s)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+- `Leonardo da Vinci’s Robot`_ (1495) – Designed a humanoid knight with mechanical movement.
+- `Jacques de Vaucanson’s Digesting Duck`_ (1738) – Created robotic figures like a mechanical duck that could "eat" and "digest."
+- `Industrial Revolution`_ (18th–19th Century) – Machines began replacing human labor in factories, setting the foundation for automation.
+
+.. _`Leonardo da Vinci’s Robot`: https://en.wikipedia.org/wiki/Leonardo%27s_robot
+.. _`Jacques de Vaucanson’s Digesting Duck`: https://en.wikipedia.org/wiki/Jacques_de_Vaucanson
+.. _`Industrial Revolution`: https://en.wikipedia.org/wiki/Industrial_Revolution
+
+The Rise of Industrial Robots (1900s–1950s)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+- **The Term “Robot” (1921)** – Czech writer `Karel Čapek`_ introduced the word *“robot”* in his play `R.U.R.`_ (Rossum’s Universal Robots).
+- **Early Cybernetics (1940s–1950s)** – Scientists like `Norbert Wiener`_ developed theories of self-regulating machines, influencing modern robotics (Cybernetics).
+
+.. _`Norbert Wiener`: https://en.wikipedia.org/wiki/Norbert_Wiener
+
+The Birth of Modern Robotics (1950s–1980s)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+- **First Industrial Robot (1961)** – `Unimate`_, created by `George Devol`_ and `Joseph Engelberger`_, was the first programmable robot used in a factory.
+- **Rise of AI & Autonomous Robots (1970s–1980s)** – Researchers developed mobile robots like `Shakey`_ (Stanford, 1966) and AI-based control systems.
+
+.. _`Unimate`: https://en.wikipedia.org/wiki/Unimate
+.. _`George Devol`: https://en.wikipedia.org/wiki/George_Devol
+.. _`Joseph Engelberger`: https://en.wikipedia.org/wiki/Joseph_Engelberger
+.. _`Shakey`: https://en.wikipedia.org/wiki/Shakey_the_robot
+
+Advanced Robotics and AI Integration (1990s–Present)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+- **Industrial Robots** – Advanced robots like `Baxter`_ and `Amazon Robotics`_ revolutionized manufacturing and logistics.
+- **Autonomous Vehicles** – Self-driving cars for robo taxi like `Waymo`_ and autonomous haulage system in mining like `AHS`_ became more advanced and bisiness-ready.
+- **Exploration Robots** – Used for planetary exploration (e.g., NASA’s `Mars rovers`_).
+- **Medical Robotics** – Robots like `da Vinci Surgical System`_ revolutionized healthcare.
+- **Personal Robots** – Devices like `Roomba`_ (vacuum robot) and `Sophia`_ (AI humanoid) became popular.
+- **Service Robots** - Assistive robots like serving robots in restaurants and hotels like `Bellabot`_.
+- **Collaborative Robots (Drones)** – Collaborative robots like UAV (Unmanned Aerial Vehicle) in drone shows and delivery services.
+
+.. _`Baxter`: https://en.wikipedia.org/wiki/Baxter_(robot)
+.. _`Amazon Robotics`: https://en.wikipedia.org/wiki/Amazon_Robotics
+.. _`Mars rovers`: https://en.wikipedia.org/wiki/Mars_rover
+.. _`Waymo`: https://waymo.com/
+.. _`AHS`: https://www.futurebridge.com/industry/perspectives-industrial-manufacturing/autonomous-haulage-systems-the-future-of-mining-operations/
+.. _`da Vinci Surgical System`: https://en.wikipedia.org/wiki/Da_Vinci_Surgical_System
+.. _`Roomba`: https://en.wikipedia.org/wiki/Roomba
+.. _`Sophia`: https://en.wikipedia.org/wiki/Sophia_(robot)
+.. _`Bellabot`: https://www.pudurobotics.com/en
+
+Key Components of Robotics
+^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Robotics consists of several essential components:
+
+#. Sensors – Gather information from the environment (e.g., Cameras, LiDAR, GNSS, Gyro, Accelerometer, Wheel encoders).
+#. Actuators – Enable movement and interaction with the world (e.g., Motors, Hydraulic systems).
+#. Computers – Process sensor data and make decisions (e.g., Micro-controllers, CPUs, GPUs).
+#. Power Supply – Provides energy to run the robot (e.g., Batteries, Solar power).
+#. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, Machine learning models, Localization, Mapping, Path planning, Control).
+
+This project, `PythonRobotics`, focuses on the software and algorithms part of robotics.
+If you are interested in `Sensors` hardware, you can check :ref:`Internal Sensors for Robots` or :ref:`External Sensors for Robots`.
diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst
new file mode 100644
index 0000000000..c47c122853
--- /dev/null
+++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst
@@ -0,0 +1,135 @@
+Python for Robotics
+----------------------
+
+A programing language, Python is used for this `PythonRobotics` project
+to achieve the purposes of this project described in the :ref:`What is PythonRobotics?`.
+
+This section explains the Python itself and features for science computing and robotics.
+
+Python for general-purpose programming
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+`Python `_ is an general-purpose programming language developed by
+`Guido van Rossum `_ from the late 1980s.
+
+It features as follows:
+
+#. High-level
+#. Interpreted
+#. Dynamic type system (also type annotation is supported)
+#. Emphasizes code readability
+#. Rapid prototyping
+#. Batteries included
+#. Interoperability for C and Fortran
+
+Due to these features, Python is one of the most popular programming language
+for educational purposes for programming beginners.
+
+Python for Scientific Computing
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Python itself was not designed for scientific computing.
+However, scientists quickly recognized its strengths.
+For example,
+
+#. High-level and interpreted features enable scientists to focus on their problems without dealing with low-level programming tasks like memory management.
+#. Code readability, rapid prototyping, and batteries included features enables scientists who are not professional programmers, to solve their problems easily.
+#. The interoperability to wrap C and Fortran libraries enables scientists to access already existed powerful and optimized scientific computing libraries.
+
+To address the more needs of scientific computing, many fundamental scientific computation libraries have been developed based on the upper features.
+
+- `NumPy `_ is the fundamental package for scientific computing with Python.
+- `SciPy `_ is a library that builds on NumPy and provides a large number of functions that operate on NumPy arrays and are useful for different types of scientific and engineering applications.
+- `Matplotlib `_ is a plotting library for the Python programming language and its numerical mathematics extension NumPy.
+- `Pandas `_ is a fast, powerful, flexible, and easy-to-use open-source data analysis and data manipulation library built on top of NumPy.
+- `SymPy `_ is a Python library for symbolic mathematics.
+- `CVXPy `_ is a Python-embedded modeling language for convex optimization problems.
+
+Also, more domain-specific libraries have been developed based on these fundamental libraries:
+
+- `Scikit-learn `_ is a free software machine learning library for the Python programming language.
+- `Scikit-image `_ is a collection of algorithms for image processing.
+- `Networkx `_ is a package for the creation, manipulation for complex networks.
+- `SunPy `_ is a community-developed free and open-source software package for solar physics.
+- `Astropy `_ is a community-developed free and open-source software package for astronomy.
+
+Currently, Python is one of the most popular programming languages for scientific computing.
+
+Python for Robotics
+^^^^^^^^^^^^^^^^^^^^
+
+Python has become an increasingly popular language in robotics.
+
+These are advantages of Python for Robotics:
+
+Simplicity and Readability
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Python's syntax is clear and concise, making it easier to learn and write code.
+This is crucial in robotics where complex algorithms and control logic are involved.
+
+
+Extensive libraries for scientific computation.
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Scientific computation routine are fundamental for robotics.
+For example:
+
+- Matrix operation is needed for rigid body transformation, state estimation, and model based control.
+- Optimization is needed for optimization based SLAM, optimal path planning, and optimal control.
+- Visualization is needed for robot teleoperation, debugging, and simulation.
+
+ROS supports Python
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+`ROS`_ (Robot Operating System) is an open-source and widely used framework for robotics development.
+It is designed to help developping complicated robotic applications.
+ROS provides essential tools, libraries, and drivers to simplify robot programming and integration.
+
+Key Features of ROS:
+
+- Modular Architecture – Uses a node-based system where different components (nodes) communicate via messages.
+- Hardware Abstraction – Supports various robots, sensors, and actuators, making development more flexible.
+- Powerful Communication System – Uses topics, services, and actions for efficient data exchange between components.
+- Rich Ecosystem – Offers many pre-built packages for navigation, perception, and manipulation.
+- Multi-language Support – Primarily uses Python and C++, but also supports other languages.
+- Simulation & Visualization – Tools like Gazebo (for simulation) and RViz (for visualization) aid in development and testing.
+- Scalability & Community Support – Widely used in academia and industry, with a large open-source community.
+
+ROS has strong Python support (`rospy`_ for ROS1 and `rclpy`_ for ROS2).
+This allows developers to easily create nodes, manage communication between
+different parts of a robot system, and utilize various ROS tools.
+
+.. _`ROS`: https://www.ros.org/
+.. _`rospy`: http://wiki.ros.org/rospy
+.. _`rclpy`: https://docs.ros.org/en/jazzy/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.html
+
+Cross-Platform Compatibility
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Python code can run on various operating systems (Windows, macOS, Linux), providing flexibility in choosing hardware platforms for robotics projects.
+
+Large Community and Support
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development.
+
+Situations which Python is NOT suitable for Robotics
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+We explained the advantages of Python for robotics.
+However, Python is not always the best choice for robotics development.
+
+These are situations where Python is NOT suitable for robotics:
+
+High-speed real-time control
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Python is an interpreted language, which means it is slower than compiled languages like C++.
+This can be a disadvantage when real-time control is required,
+such as in high-speed motion control or safety-critical systems.
+
+So, for these applications, we recommend to understand the each algorithm you
+needed using this project and implement it in other suitable languages like C++.
+
+Resource-constrained systems
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Python is a high-level language that requires more memory and processing power
+compared to low-level languages.
+So, it is difficult to run Python on resource-constrained systems like
+microcontrollers or embedded devices.
+In such cases, C or C++ is more suitable for these applications.
diff --git a/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst
new file mode 100644
index 0000000000..0ed51e961b
--- /dev/null
+++ b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst
@@ -0,0 +1,68 @@
+Technologies for Robotics
+-------------------------
+
+The field of robotics needs wide areas of technologies such as mechanical engineering,
+electrical engineering, computer science, and artificial intelligence (AI).
+This project, `PythonRobotics`, only focus on computer science and artificial intelligence.
+
+The technologies for robotics are categorized as following 3 categories:
+
+#. `Autonomous Navigation`_
+#. `Manipulation`_
+#. `Robot type specific technologies`_
+
+.. _`Autonomous Navigation`:
+
+Autonomous Navigation
+^^^^^^^^^^^^^^^^^^^^^^^^
+Autonomous navigation is a capability that can move to a goal over long
+periods of time without any external control by an operator.
+
+To achieve autonomous navigation, the robot needs to have the following technologies:
+- It needs to know where it is (localization)
+- Where it is safe (mapping)
+- Where is is safe and where the robot is in the map (Simultaneous Localization and Mapping (SLAM))
+- Where and how to move (path planning)
+- How to control its motion (path following).
+
+The autonomous system would not work correctly if any of these technologies is missing.
+
+In recent years, autonomous navigation technologies have received huge
+attention in many fields.
+For example, self-driving cars, drones, and autonomous mobile robots in indoor and outdoor environments.
+
+In this project, we provide many algorithms, sample codes,
+and documentations for autonomous navigation.
+
+#. :ref:`Localization`
+#. :ref:`Mapping`
+#. :ref:`SLAM`
+#. :ref:`Path planning`
+#. :ref:`Path tracking`
+
+
+
+.. _`Manipulation`:
+
+Manipulation
+^^^^^^^^^^^^^^^^^^^^^^^^
+
+#. :ref:`Arm Navigation`
+
+.. _`Robot type specific technologies`:
+
+Robot type specific technologies
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+#. :ref:`Aerial Navigation`
+#. :ref:`Bipedal`
+#. :ref:`Inverted Pendulum`
+
+
+Additional Information
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+#. :ref:`utils`
+#. :ref:`Appendix`
+
+
diff --git a/docs/modules/1_introduction/introduction_main.rst b/docs/modules/1_introduction/introduction_main.rst
new file mode 100644
index 0000000000..1871dfc3b1
--- /dev/null
+++ b/docs/modules/1_introduction/introduction_main.rst
@@ -0,0 +1,18 @@
+.. _Introduction:
+
+Introduction
+============
+
+PythonRobotics is composed of two words: "Python" and "Robotics".
+Therefore, I will first explain these two topics, Robotics and Python.
+After that, I will provide an overview of the robotics technologies
+covered in PythonRobotics.
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Table of Contents
+
+ 1_definition_of_robotics/definition_of_robotics
+ 2_python_for_robotics/python_for_robotics
+ 3_technologies_for_robotics/technologies_for_robotics
+
diff --git a/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst b/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst
new file mode 100644
index 0000000000..214e645d10
--- /dev/null
+++ b/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst
@@ -0,0 +1,12 @@
+Ensamble Kalman Filter Localization
+-----------------------------------
+
+.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/ensamble_kalman_filter/animation.gif
+
+This is a sensor fusion localization with Ensamble Kalman Filter(EnKF).
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Localization.ensemble_kalman_filter.ensemble_kalman_filter.enkf_localization
+
diff --git a/docs/modules/2_localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png b/docs/modules/2_localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png
new file mode 100644
index 0000000000..595b651bd2
Binary files /dev/null and b/docs/modules/2_localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png differ
diff --git a/docs/modules/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png
similarity index 100%
rename from docs/modules/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png
rename to docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png
diff --git a/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst
new file mode 100644
index 0000000000..adb41e5e40
--- /dev/null
+++ b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst
@@ -0,0 +1,252 @@
+
+Extended Kalman Filter Localization
+-----------------------------------
+
+Position Estimation Kalman Filter
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. image:: extended_kalman_filter_localization_1_0.png
+ :width: 600px
+
+
+
+.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif
+
+
+This is a sensor fusion localization with Extended Kalman Filter(EKF).
+
+The blue line is true trajectory, the black line is dead reckoning
+trajectory,
+
+the green point is positioning observation (ex. GPS), and the red line
+is estimated trajectory with EKF.
+
+The red ellipse is estimated covariance ellipse with EKF.
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: Localization.extended_kalman_filter.extended_kalman_filter.ekf_estimation
+
+Extended Kalman Filter algorithm
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Localization process using Extended Kalman Filter:EKF is
+
+=== Predict ===
+
+:math:`x_{Pred} = Fx_t+Bu_t`
+
+:math:`P_{Pred} = J_f P_t J_f^T + Q`
+
+=== Update ===
+
+:math:`z_{Pred} = Hx_{Pred}`
+
+:math:`y = z - z_{Pred}`
+
+:math:`S = J_g P_{Pred}.J_g^T + R`
+
+:math:`K = P_{Pred}.J_g^T S^{-1}`
+
+:math:`x_{t+1} = x_{Pred} + Ky`
+
+:math:`P_{t+1} = ( I - K J_g) P_{Pred}`
+
+
+
+Filter design
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+In this simulation, the robot has a state vector includes 4 states at
+time :math:`t`.
+
+.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t]
+
+x, y are a 2D x-y position, :math:`\phi` is orientation, and v is
+velocity.
+
+In the code, “xEst” means the state vector.
+`code `__
+
+And, :math:`P_t` is covariace matrix of the state,
+
+:math:`Q` is covariance matrix of process noise,
+
+:math:`R` is covariance matrix of observation noise at time :math:`t`
+
+
+
+The robot has a speed sensor and a gyro sensor.
+
+So, the input vecor can be used as each time step
+
+.. math:: \textbf{u}_t=[v_t, \omega_t]
+
+Also, the robot has a GNSS sensor, it means that the robot can observe
+x-y position at each time.
+
+.. math:: \textbf{z}_t=[x_t,y_t]
+
+The input and observation vector includes sensor noise.
+
+In the code, “observation” function generates the input and observation
+vector with noise
+`code `__
+
+
+Motion Model
+~~~~~~~~~~~~~~~~~
+
+The robot model is
+
+.. math:: \dot{x} = v \cos(\phi)
+
+.. math:: \dot{y} = v \sin(\phi)
+
+.. math:: \dot{\phi} = \omega
+
+So, the motion model is
+
+.. math:: \textbf{x}_{t+1} = f(\textbf{x}_t, \textbf{u}_t) = F\textbf{x}_t+B\textbf{u}_t
+
+where
+
+:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} B= \begin{bmatrix} cos(\phi) \Delta t & 0\\ sin(\phi) \Delta t & 0\\ 0 & \Delta t\\ 1 & 0\\ \end{bmatrix} \end{equation*}`
+
+:math:`\Delta t` is a time interval.
+
+This is implemented at
+`code `__
+
+The motion function is that
+
+:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \\ w' \\ v' \end{bmatrix} = f(\textbf{x}, \textbf{u}) = \begin{bmatrix} x + v\cos(\phi)\Delta t \\ y + v\sin(\phi)\Delta t \\ \phi + \omega \Delta t \\ v \end{bmatrix} \end{equation*}`
+
+Its Jacobian matrix is
+
+:math:`\begin{equation*} J_f = \begin{bmatrix} \frac{\partial x'}{\partial x}& \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{\partial v}\\ \frac{\partial \phi'}{\partial x}& \frac{\partial \phi'}{\partial y} & \frac{\partial \phi'}{\partial \phi} & \frac{\partial \phi'}{\partial v}\\ \frac{\partial v'}{\partial x}& \frac{\partial v'}{\partial y} & \frac{\partial v'}{\partial \phi} & \frac{\partial v'}{\partial v} \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & -v \sin(\phi) \Delta t & \cos(\phi) \Delta t\\ 0 & 1 & v \cos(\phi) \Delta t & \sin(\phi) \Delta t\\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix} \end{equation*}`
+
+Observation Model
+~~~~~~~~~~~~~~~~~
+
+The robot can get x-y position information from GPS.
+
+So GPS Observation model is
+
+.. math:: \textbf{z}_{t} = g(\textbf{x}_t) = H \textbf{x}_t
+
+where
+
+:math:`\begin{equation*} H = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
+
+The observation function states that
+
+:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \end{bmatrix} = g(\textbf{x}) = \begin{bmatrix} x \\ y \end{bmatrix} \end{equation*}`
+
+Its Jacobian matrix is
+
+:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v}\\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}`
+
+
+Kalman Filter with Speed Scale Factor Correction
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+This is a Extended kalman filter (EKF) localization with velocity correction.
+
+This is for correcting the vehicle speed measured with scale factor errors due to factors such as wheel wear.
+
+
+In this simulation, the robot has a state vector includes 5 states at
+time :math:`t`.
+
+.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t, s_t]
+
+x, y are a 2D x-y position, :math:`\phi` is orientation, v is
+velocity, and s is a scale factor of velocity.
+
+In the code, “xEst” means the state vector.
+`code `__
+
+The rest is the same as the Position Estimation Kalman Filter.
+
+.. image:: ekf_with_velocity_correction_1_0.png
+ :width: 600px
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: Localization.extended_kalman_filter.ekf_with_velocity_correction.ekf_estimation
+
+
+Motion Model
+~~~~~~~~~~~~
+
+The robot model is
+
+.. math:: \dot{x} = v s \cos(\phi)
+
+.. math:: \dot{y} = v s \sin(\phi)
+
+.. math:: \dot{\phi} = \omega
+
+So, the motion model is
+
+.. math:: \textbf{x}_{t+1} = f(\textbf{x}_t, \textbf{u}_t) = F\textbf{x}_t+B\textbf{u}_t
+
+where
+
+:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 & 0 & 0\\ 0 & 1 & 0 & 0 & 0\\ 0 & 0 & 1 & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 1\\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} B= \begin{bmatrix} cos(\phi) \Delta t s & 0\\ sin(\phi) \Delta t s & 0\\ 0 & \Delta t\\ 1 & 0\\ 0 & 0\\ \end{bmatrix} \end{equation*}`
+
+:math:`\Delta t` is a time interval.
+
+This is implemented at
+`code `__
+
+The motion function is that
+
+:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \\ w' \\ v' \end{bmatrix} = f(\textbf{x}, \textbf{u}) = \begin{bmatrix} x + v s \cos(\phi)\Delta t \\ y + v s \sin(\phi)\Delta t \\ \phi + \omega \Delta t \\ v \end{bmatrix} \end{equation*}`
+
+Its Jacobian matrix is
+
+:math:`\begin{equation*} J_f = \begin{bmatrix} \frac{\partial x'}{\partial x}& \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v} & \frac{\partial x'}{\partial s}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{\partial v} & \frac{\partial y'}{\partial s}\\ \frac{\partial \phi'}{\partial x}& \frac{\partial \phi'}{\partial y} & \frac{\partial \phi'}{\partial \phi} & \frac{\partial \phi'}{\partial v} & \frac{\partial \phi'}{\partial s}\\ \frac{\partial v'}{\partial x}& \frac{\partial v'}{\partial y} & \frac{\partial v'}{\partial \phi} & \frac{\partial v'}{\partial v} & \frac{\partial v'}{\partial s} \\ \frac{\partial s'}{\partial x}& \frac{\partial s'}{\partial y} & \frac{\partial s'}{\partial \phi} & \frac{\partial s'}{\partial v} & \frac{\partial s'}{\partial s} \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & -v s \sin(\phi) \Delta t & s \cos(\phi) \Delta t & \cos(\phi) v \Delta t\\ 0 & 1 & v s \cos(\phi) \Delta t & s \sin(\phi) \Delta t & v \sin(\phi) \Delta t\\ 0 & 0 & 1 & 0 & 0 \\ 0 & 0 & 0 & 1 & 0 \end{bmatrix} \end{equation*}`
+
+
+Observation Model
+~~~~~~~~~~~~~~~~~
+
+The robot can get x-y position information from GPS.
+
+So GPS Observation model is
+
+.. math:: \textbf{z}_{t} = g(\textbf{x}_t) = H \textbf{x}_t
+
+where
+
+:math:`\begin{equation*} H = \begin{bmatrix} 1 & 0 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
+
+The observation function states that
+
+:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \end{bmatrix} = g(\textbf{x}) = \begin{bmatrix} x \\ y \end{bmatrix} \end{equation*}`
+
+Its Jacobian matrix is
+
+:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v} & \frac{\partial x'}{\partial s}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v} & \frac{\partial y'}{ \partial s}\\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & 0 & 0 & 0\\ 0 & 1 & 0 & 0 & 0\\ \end{bmatrix} \end{equation*}`
+
+
+
+Reference
+^^^^^^^^^^^
+
+- `PROBABILISTIC-ROBOTICS.ORG `__
diff --git a/docs/modules/2_localization/histogram_filter_localization/1.png b/docs/modules/2_localization/histogram_filter_localization/1.png
new file mode 100644
index 0000000000..5e3137cc1a
Binary files /dev/null and b/docs/modules/2_localization/histogram_filter_localization/1.png differ
diff --git a/docs/modules/2_localization/histogram_filter_localization/2.png b/docs/modules/2_localization/histogram_filter_localization/2.png
new file mode 100644
index 0000000000..2f4c2235df
Binary files /dev/null and b/docs/modules/2_localization/histogram_filter_localization/2.png differ
diff --git a/docs/modules/2_localization/histogram_filter_localization/3.png b/docs/modules/2_localization/histogram_filter_localization/3.png
new file mode 100644
index 0000000000..e7927366a8
Binary files /dev/null and b/docs/modules/2_localization/histogram_filter_localization/3.png differ
diff --git a/docs/modules/2_localization/histogram_filter_localization/4.png b/docs/modules/2_localization/histogram_filter_localization/4.png
new file mode 100644
index 0000000000..c7838cf26a
Binary files /dev/null and b/docs/modules/2_localization/histogram_filter_localization/4.png differ
diff --git a/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst b/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst
new file mode 100644
index 0000000000..3a175b1316
--- /dev/null
+++ b/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst
@@ -0,0 +1,119 @@
+Histogram filter localization
+-----------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/histogram_filter/animation.gif
+
+This is a 2D localization example with Histogram filter.
+
+The red cross is true position, black points are RFID positions.
+
+The blue grid shows a position probability of histogram filter.
+
+In this simulation, we assume the robot's yaw orientation and RFID's positions are known,
+but x,y positions are unknown.
+
+The filter uses speed input and range observations from RFID for localization.
+
+Initial position information is not needed.
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: Localization.histogram_filter.histogram_filter.histogram_filter_localization
+
+Filtering algorithm
+~~~~~~~~~~~~~~~~~~~~
+
+Histogram filter is a discrete Bayes filter in continuous space.
+
+It uses regular girds to manage probability of the robot existence.
+
+If a grid has higher probability, it means that the robot is likely to be there.
+
+In the simulation, we want to estimate x-y position, so we use 2D grid data.
+
+There are 4 steps for the histogram filter to estimate the probability distribution.
+
+Step1: Filter initialization
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Histogram filter does not need initial position information.
+
+In that case, we can initialize each grid probability as a same value.
+
+If we can use initial position information, we can set initial probabilities based on it.
+
+:ref:`gaussian_grid_map` might be useful when the initial position information is provided as gaussian distribution.
+
+Step2: Predict probability by motion
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+In histogram filter, when a robot move to a next grid,
+all probability information of each grid are shifted towards the movement direction.
+
+This process represents the change in the probability distribution as the robot moves.
+
+After the robot has moved, the probability distribution needs reflect
+the estimation error due to the movement.
+
+For example, the position probability is peaky with observations:
+
+.. image:: 1.png
+ :width: 400px
+
+But, the probability is getting uncertain without observations:
+
+.. image:: 2.png
+ :width: 400px
+
+
+The `gaussian filter `_
+is used in the simulation for adding noize.
+
+Step3: Update probability by observation
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+In this step, all probabilities are updated by observations,
+this is the update step of bayesian filter.
+
+The probability update formula is different by the used sensor model.
+
+This simulation uses range observation model.
+
+The probability of each grid is updated by this formula:
+
+.. math:: p_t=p_{t-1}*h(z)
+
+.. math:: h(z)=\frac{\exp \left(-(d - z)^{2} / 2\right)}{\sqrt{2 \pi}}
+
+- :math:`p_t` is the probability at the time `t`.
+
+- :math:`h(z)` is the observation probability with the observation `z`.
+
+- :math:`d` is the known distance from the RD-ID to the grid center.
+
+When the `d` is 3.0, the `h(z)` distribution is:
+
+.. image:: 4.png
+ :width: 400px
+
+The observation probability distribution looks a circle when a RF-ID is observed:
+
+.. image:: 3.png
+ :width: 400px
+
+Step4: Estimate position from probability
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+In each time step, we can calculate the final robot position from the current probability distribution.
+There are two ways to calculate the final positions:
+
+1. Using the maximum probability grid position.
+
+2. Using the average of probability weighted grind position.
+
+
+
+Reference
+~~~~~~~~~~~
+
+- `_PROBABILISTIC ROBOTICS: `_
+- `Robust Vehicle Localization in Urban Environments Using Probabilistic Maps `_
diff --git a/docs/modules/2_localization/localization_main.rst b/docs/modules/2_localization/localization_main.rst
new file mode 100644
index 0000000000..770a234b69
--- /dev/null
+++ b/docs/modules/2_localization/localization_main.rst
@@ -0,0 +1,17 @@
+.. _`Localization`:
+
+Localization
+============
+Localization is the ability of a robot to know its position and orientation with sensors such as Global Navigation Satellite System:GNSS etc. In localization, Bayesian filters such as Kalman filters, histogram filter, and particle filter are widely used[31]. Fig.2 shows localization simulations using histogram filter and particle filter.
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ extended_kalman_filter_localization_files/extended_kalman_filter_localization
+ ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization
+ unscented_kalman_filter_localization/unscented_kalman_filter_localization
+ histogram_filter_localization/histogram_filter_localization
+ particle_filter_localization/particle_filter_localization
+
+
diff --git a/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst b/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst
new file mode 100644
index 0000000000..d648d8e080
--- /dev/null
+++ b/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst
@@ -0,0 +1,43 @@
+Particle filter localization
+----------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/particle_filter/animation.gif
+
+This is a sensor fusion localization with Particle Filter(PF).
+
+The blue line is true trajectory, the black line is dead reckoning
+trajectory,
+
+and the red line is estimated trajectory with PF.
+
+It is assumed that the robot can measure a distance from landmarks
+(RFID).
+
+This measurements are used for PF localization.
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: Localization.particle_filter.particle_filter.pf_localization
+
+
+How to calculate covariance matrix from particles
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The covariance matrix :math:`\Xi` from particle information is calculated by the following equation:
+
+.. math:: \Xi_{j,k}=\frac{1}{1-\sum^N_{i=1}(w^i)^2}\sum^N_{i=1}w^i(x^i_j-\mu_j)(x^i_k-\mu_k)
+
+- :math:`\Xi_{j,k}` is covariance matrix element at row :math:`i` and column :math:`k`.
+
+- :math:`w^i` is the weight of the :math:`i` th particle.
+
+- :math:`x^i_j` is the :math:`j` th state of the :math:`i` th particle.
+
+- :math:`\mu_j` is the :math:`j` th mean state of particles.
+
+Reference
+~~~~~~~~~~~
+
+- `_PROBABILISTIC ROBOTICS: `_
+- `Improving the particle filter in high dimensions using conjugate artificial process noise `_
diff --git a/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst b/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst
new file mode 100644
index 0000000000..a7a5aab61b
--- /dev/null
+++ b/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst
@@ -0,0 +1,19 @@
+Unscented Kalman Filter localization
+------------------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/unscented_kalman_filter/animation.gif
+
+This is a sensor fusion localization with Unscented Kalman Filter(UKF).
+
+The lines and points are same meaning of the EKF simulation.
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: Localization.unscented_kalman_filter.unscented_kalman_filter.ukf_estimation
+
+
+Reference
+~~~~~~~~~~~
+
+- `Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization `_
diff --git a/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst b/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst
new file mode 100644
index 0000000000..e243529a9c
--- /dev/null
+++ b/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst
@@ -0,0 +1,17 @@
+Object shape recognition using circle fitting
+---------------------------------------------
+
+This is an object shape recognition using circle fitting.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/circle_fitting/animation.gif
+
+The blue circle is the true object shape.
+
+The red crosses are observations from a ranging sensor.
+
+The red circle is the estimated object shape using circle fitting.
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.circle_fitting.circle_fitting.circle_fitting
diff --git a/docs/modules/3_mapping/distance_map/distance_map.png b/docs/modules/3_mapping/distance_map/distance_map.png
new file mode 100644
index 0000000000..2d89252a70
Binary files /dev/null and b/docs/modules/3_mapping/distance_map/distance_map.png differ
diff --git a/docs/modules/3_mapping/distance_map/distance_map_main.rst b/docs/modules/3_mapping/distance_map/distance_map_main.rst
new file mode 100644
index 0000000000..ec60e752c9
--- /dev/null
+++ b/docs/modules/3_mapping/distance_map/distance_map_main.rst
@@ -0,0 +1,27 @@
+Distance Map
+------------
+
+This is an implementation of the Distance Map algorithm for path planning.
+
+The Distance Map algorithm computes the unsigned distance field (UDF) and signed distance field (SDF) from a boolean field representing obstacles.
+
+The UDF gives the distance from each point to the nearest obstacle. The SDF gives positive distances for points outside obstacles and negative distances for points inside obstacles.
+
+Example
+~~~~~~~
+
+The algorithm is demonstrated on a simple 2D grid with obstacles:
+
+.. image:: distance_map.png
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.DistanceMap.distance_map.compute_sdf
+
+.. autofunction:: Mapping.DistanceMap.distance_map.compute_udf
+
+References
+~~~~~~~~~~
+
+- `Distance Transforms of Sampled Functions `_ paper by Pedro F. Felzenszwalb and Daniel P. Huttenlocher.
\ No newline at end of file
diff --git a/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst b/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst
new file mode 100644
index 0000000000..50033d2a20
--- /dev/null
+++ b/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst
@@ -0,0 +1,14 @@
+.. _gaussian_grid_map:
+
+Gaussian grid map
+-----------------
+
+This is a 2D Gaussian grid mapping example.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/gaussian_grid_map/animation.gif
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.gaussian_grid_map.gaussian_grid_map.generate_gaussian_grid_map
+
diff --git a/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst b/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst
new file mode 100644
index 0000000000..0ece604009
--- /dev/null
+++ b/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst
@@ -0,0 +1,12 @@
+k-means object clustering
+-------------------------
+
+This is a 2D object clustering with k-means algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/kmeans_clustering/animation.gif
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.kmeans_clustering.kmeans_clustering.kmeans_clustering
+
diff --git a/Mapping/lidar_to_grid_map/grid_map_example.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/grid_map_example.png
similarity index 100%
rename from Mapping/lidar_to_grid_map/grid_map_example.png
rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/grid_map_example.png
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png
new file mode 100644
index 0000000000..0a03f61c86
Binary files /dev/null and b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png differ
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png
new file mode 100644
index 0000000000..6a89b3e0fa
Binary files /dev/null and b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png differ
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png
new file mode 100644
index 0000000000..1272a77a5e
Binary files /dev/null and b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png differ
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png
new file mode 100644
index 0000000000..a7940ee6b0
Binary files /dev/null and b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png differ
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png
new file mode 100644
index 0000000000..49c588de35
Binary files /dev/null and b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png differ
diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst
new file mode 100644
index 0000000000..29f5878e48
--- /dev/null
+++ b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst
@@ -0,0 +1,204 @@
+Lidar to grid map
+--------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/lidar_to_grid_map/animation.gif
+
+This simple tutorial shows how to read LIDAR (range) measurements from a
+file and convert it to occupancy grid.
+
+Occupancy grid maps (*Hans Moravec, A.E. Elfes: High resolution maps
+from wide angle sonar, Proc. IEEE Int. Conf. Robotics Autom. (1985)*)
+are a popular, probabilistic approach to represent the environment. The
+grid is basically discrete representation of the environment, which
+shows if a grid cell is occupied or not. Here the map is represented as
+a ``numpy array``, and numbers close to 1 means the cell is occupied
+(*marked with red on the next image*), numbers close to 0 means they are
+free (*marked with green*). The grid has the ability to represent
+unknown (unobserved) areas, which are close to 0.5.
+
+.. figure:: grid_map_example.png
+
+In order to construct the grid map from the measurement we need to
+discretise the values. But, first let’s need to ``import`` some
+necessary packages.
+
+.. code:: ipython3
+
+ import math
+ import numpy as np
+ import matplotlib.pyplot as plt
+ from math import cos, sin, radians, pi
+
+The measurement file contains the distances and the corresponding angles
+in a ``csv`` (comma separated values) format. Let’s write the
+``file_read`` method:
+
+.. code:: ipython3
+
+ def file_read(f):
+ """
+ Reading LIDAR laser beams (angles and corresponding distance data)
+ """
+ measures = [line.split(",") for line in open(f)]
+ angles = []
+ distances = []
+ for measure in measures:
+ angles.append(float(measure[0]))
+ distances.append(float(measure[1]))
+ angles = np.array(angles)
+ distances = np.array(distances)
+ return angles, distances
+
+From the distances and the angles it is easy to determine the ``x`` and
+``y`` coordinates with ``sin`` and ``cos``. In order to display it
+``matplotlib.pyplot`` (``plt``) is used.
+
+.. code:: ipython3
+
+ ang, dist = file_read("lidar01.csv")
+ ox = np.sin(ang) * dist
+ oy = np.cos(ang) * dist
+ plt.figure(figsize=(6,10))
+ plt.plot([oy, np.zeros(np.size(oy))], [ox, np.zeros(np.size(oy))], "ro-") # lines from 0,0 to the
+ plt.axis("equal")
+ bottom, top = plt.ylim() # return the current ylim
+ plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation
+ plt.grid(True)
+ plt.show()
+
+
+
+.. image:: lidar_to_grid_map_tutorial_5_0.png
+
+
+The ``lidar_to_grid_map.py`` contains handy functions which can used to
+convert a 2D range measurement to a grid map. For example the
+``bresenham`` gives the a straight line between two points in a grid
+map. Let’s see how this works.
+
+.. code:: ipython3
+
+ import lidar_to_grid_map as lg
+ map1 = np.ones((50, 50)) * 0.5
+ line = lg.bresenham((2, 2), (40, 30))
+ for l in line:
+ map1[l[0]][l[1]] = 1
+ plt.imshow(map1)
+ plt.colorbar()
+ plt.show()
+
+
+
+.. image:: lidar_to_grid_map_tutorial_7_0.png
+
+
+.. code:: ipython3
+
+ line = lg.bresenham((2, 30), (40, 30))
+ for l in line:
+ map1[l[0]][l[1]] = 1
+ line = lg.bresenham((2, 30), (2, 2))
+ for l in line:
+ map1[l[0]][l[1]] = 1
+ plt.imshow(map1)
+ plt.colorbar()
+ plt.show()
+
+
+
+.. image:: lidar_to_grid_map_tutorial_8_0.png
+
+
+To fill empty areas, a queue-based algorithm can be used that can be
+used on an initialized occupancy map. The center point is given: the
+algorithm checks for neighbour elements in each iteration, and stops
+expansion on obstacles and free boundaries.
+
+.. code:: ipython3
+
+ from collections import deque
+ def flood_fill(cpoint, pmap):
+ """
+ cpoint: starting point (x,y) of fill
+ pmap: occupancy map generated from Bresenham ray-tracing
+ """
+ # Fill empty areas with queue method
+ sx, sy = pmap.shape
+ fringe = deque()
+ fringe.appendleft(cpoint)
+ while fringe:
+ n = fringe.pop()
+ nx, ny = n
+ # West
+ if nx > 0:
+ if pmap[nx - 1, ny] == 0.5:
+ pmap[nx - 1, ny] = 0.0
+ fringe.appendleft((nx - 1, ny))
+ # East
+ if nx < sx - 1:
+ if pmap[nx + 1, ny] == 0.5:
+ pmap[nx + 1, ny] = 0.0
+ fringe.appendleft((nx + 1, ny))
+ # North
+ if ny > 0:
+ if pmap[nx, ny - 1] == 0.5:
+ pmap[nx, ny - 1] = 0.0
+ fringe.appendleft((nx, ny - 1))
+ # South
+ if ny < sy - 1:
+ if pmap[nx, ny + 1] == 0.5:
+ pmap[nx, ny + 1] = 0.0
+ fringe.appendleft((nx, ny + 1))
+
+This algotihm will fill the area bounded by the yellow lines starting
+from a center point (e.g. (10, 20)) with zeros:
+
+.. code:: ipython3
+
+ flood_fill((10, 20), map1)
+ map_float = np.array(map1)/10.0
+ plt.imshow(map1)
+ plt.colorbar()
+ plt.show()
+
+
+
+.. image:: lidar_to_grid_map_tutorial_12_0.png
+
+
+Let’s use this flood fill on real data:
+
+.. code:: ipython3
+
+ xyreso = 0.02 # x-y grid resolution
+ yawreso = math.radians(3.1) # yaw angle resolution [rad]
+ ang, dist = file_read("lidar01.csv")
+ ox = np.sin(ang) * dist
+ oy = np.cos(ang) * dist
+ pmap, minx, maxx, miny, maxy, xyreso = lg.generate_ray_casting_grid_map(ox, oy, xyreso, False)
+ xyres = np.array(pmap).shape
+ plt.figure(figsize=(20,8))
+ plt.subplot(122)
+ plt.imshow(pmap, cmap = "PiYG_r")
+ plt.clim(-0.4, 1.4)
+ plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor = True)
+ plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor = True)
+ plt.grid(True, which="minor", color="w", linewidth = .6, alpha = 0.5)
+ plt.colorbar()
+ plt.show()
+
+
+.. parsed-literal::
+
+ The grid map is 150 x 100 .
+
+
+
+.. image:: lidar_to_grid_map_tutorial_14_1.png
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.lidar_to_grid_map.lidar_to_grid_map.main
+
+
diff --git a/docs/modules/3_mapping/mapping_main.rst b/docs/modules/3_mapping/mapping_main.rst
new file mode 100644
index 0000000000..34a3744893
--- /dev/null
+++ b/docs/modules/3_mapping/mapping_main.rst
@@ -0,0 +1,20 @@
+.. _`Mapping`:
+
+Mapping
+=======
+Mapping is the ability of a robot to understand its surroundings with external sensors such as LIDAR and camera. Robots have to recognize the position and shape of obstacles to avoid them. In mapping, grid mapping and machine learning algorithms are widely used[31][18]. Fig.3 shows mapping simulation results using grid mapping with 2D ray casting and 2D object clustering with k-means algorithm.
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ gaussian_grid_map/gaussian_grid_map
+ ndt_map/ndt_map
+ ray_casting_grid_map/ray_casting_grid_map
+ lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial
+ point_cloud_sampling/point_cloud_sampling
+ k_means_object_clustering/k_means_object_clustering
+ circle_fitting/circle_fitting
+ rectangle_fitting/rectangle_fitting
+ normal_vector_estimation/normal_vector_estimation
+ distance_map/distance_map
diff --git a/docs/modules/3_mapping/ndt_map/grid_clustering.png b/docs/modules/3_mapping/ndt_map/grid_clustering.png
new file mode 100644
index 0000000000..c53590287a
Binary files /dev/null and b/docs/modules/3_mapping/ndt_map/grid_clustering.png differ
diff --git a/docs/modules/3_mapping/ndt_map/ndt_map1.png b/docs/modules/3_mapping/ndt_map/ndt_map1.png
new file mode 100644
index 0000000000..1f34b9a66a
Binary files /dev/null and b/docs/modules/3_mapping/ndt_map/ndt_map1.png differ
diff --git a/docs/modules/3_mapping/ndt_map/ndt_map2.png b/docs/modules/3_mapping/ndt_map/ndt_map2.png
new file mode 100644
index 0000000000..b997062979
Binary files /dev/null and b/docs/modules/3_mapping/ndt_map/ndt_map2.png differ
diff --git a/docs/modules/3_mapping/ndt_map/ndt_map_main.rst b/docs/modules/3_mapping/ndt_map/ndt_map_main.rst
new file mode 100644
index 0000000000..bfc3936314
--- /dev/null
+++ b/docs/modules/3_mapping/ndt_map/ndt_map_main.rst
@@ -0,0 +1,53 @@
+.. _ndt_map:
+
+Normal Distance Transform (NDT) map
+------------------------------------
+
+This is a NDT mapping example.
+
+Normal Distribution Transform (NDT) is a map representation that uses normal distribution for observation point modeling.
+
+Normal Distribution
+~~~~~~~~~~~~~~~~~~~~~
+
+Normal distribution consists of two parameters: mean :math:`\mu` and covariance :math:`\Sigma`.
+
+:math:`\mathbf{X} \sim \mathcal{N}(\boldsymbol{\mu}, \boldsymbol{\Sigma})`
+
+In the 2D case, :math:`\boldsymbol{\mu}` is a 2D vector and :math:`\boldsymbol{\Sigma}` is a 2x2 matrix.
+
+In the matrix form, the probability density function of thr normal distribution is:
+
+:math:`X=\frac{1}{\sqrt{(2 \pi)^2|\Sigma|}} \exp \left\{-\frac{1}{2}^t(x-\mu) \sum^{-1}(x-\mu)\right\}`
+
+Normal Distance Transform mapping steps
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+NDT mapping consists of two steps:
+
+When we have a new observation like this:
+
+.. figure:: raw_observations.png
+
+First, we need to cluster the observation points.
+This is done by using a grid based clustering algorithm.
+
+The result is:
+
+.. figure:: grid_clustering.png
+
+Then, we need to fit a normal distribution to each grid cluster.
+
+Black ellipse shows each NDT grid like this:
+
+.. figure:: ndt_map1.png
+
+.. figure:: ndt_map2.png
+
+API
+~~~~~
+
+.. autoclass:: Mapping.ndt_map.ndt_map.NDTMap
+ :members:
+ :class-doc-from: class
+
diff --git a/docs/modules/3_mapping/ndt_map/raw_observations.png b/docs/modules/3_mapping/ndt_map/raw_observations.png
new file mode 100644
index 0000000000..c1a0dd4778
Binary files /dev/null and b/docs/modules/3_mapping/ndt_map/raw_observations.png differ
diff --git a/docs/modules/3_mapping/normal_vector_estimation/normal_vector_calc.png b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_calc.png
new file mode 100644
index 0000000000..63e2cdade7
Binary files /dev/null and b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_calc.png differ
diff --git a/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst
new file mode 100644
index 0000000000..68a19e1534
--- /dev/null
+++ b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst
@@ -0,0 +1,74 @@
+Normal vector estimation
+-------------------------
+
+
+Normal vector calculation of a 3D triangle
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+A 3D point is as a vector:
+
+.. math:: p = [x, y, z]
+
+When there are 3 points in 3D space, :math:`p_1, p_2, p_3`,
+
+we can calculate a normal vector n of a 3D triangle which is consisted of the points.
+
+.. math:: n = \frac{v1 \times v2}{|v1 \times v2|}
+
+where
+
+.. math:: v1 = p2 - p1
+
+.. math:: v2 = p3 - p1
+
+This is an example of normal vector calculation:
+
+.. figure:: normal_vector_calc.png
+
+Code Link
+==========
+
+.. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.calc_normal_vector
+
+Normal vector estimation with RANdam SAmpling Consensus(RANSAC)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Consider the problem of estimating the normal vector of a plane based on a
+set of N 3D points where a plane can be observed.
+
+There is a way that uses all point cloud data to estimate a plane and
+a normal vector using the `least-squares method `_
+
+However, this method is vulnerable to noise of the point cloud.
+
+In this document, we will use a method that uses
+`RANdam SAmpling Consensus(RANSAC) `_
+to estimate a plane and a normal vector.
+
+RANSAC is a robust estimation methods for data set with outliers.
+
+
+
+This RANSAC based normal vector estimation method is as follows:
+
+#. Select 3 points randomly from the point cloud.
+
+#. Calculate a normal vector of a plane which is consists of the sampled 3 points.
+
+#. Calculate the distance between the calculated plane and the all point cloud.
+
+#. If the distance is less than a threshold, the point is considered to be an inlier.
+
+#. Repeat the above steps until the inlier ratio is greater than a threshold.
+
+
+
+This is an example of RANSAC based normal vector estimation:
+
+.. figure:: ransac_normal_vector_estimation.png
+
+Code Link
+==========
+
+.. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.ransac_normal_vector_estimation
+
diff --git a/docs/modules/3_mapping/normal_vector_estimation/ransac_normal_vector_estimation.png b/docs/modules/3_mapping/normal_vector_estimation/ransac_normal_vector_estimation.png
new file mode 100644
index 0000000000..e9b661e79c
Binary files /dev/null and b/docs/modules/3_mapping/normal_vector_estimation/ransac_normal_vector_estimation.png differ
diff --git a/docs/modules/3_mapping/point_cloud_sampling/farthest_point_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/farthest_point_sampling.png
new file mode 100644
index 0000000000..6024a5f2d5
Binary files /dev/null and b/docs/modules/3_mapping/point_cloud_sampling/farthest_point_sampling.png differ
diff --git a/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst b/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst
new file mode 100644
index 0000000000..8cb08d4b78
--- /dev/null
+++ b/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst
@@ -0,0 +1,70 @@
+.. _point_cloud_sampling:
+
+Point cloud Sampling
+----------------------
+
+This sections explains point cloud sampling algorithms in PythonRobotics.
+
+Point clouds are two-dimensional and three-dimensional based data
+acquired by external sensors like LIDAR, cameras, etc.
+In general, Point Cloud data is very large in number of data.
+So, if you process all the data, computation time might become an issue.
+
+Point cloud sampling is a technique for solving this computational complexity
+issue by extracting only representative point data and thinning the point
+cloud data without compromising the performance of processing using the point
+cloud data.
+
+Voxel Point Sampling
+~~~~~~~~~~~~~~~~~~~~~~~~
+.. figure:: voxel_point_sampling.png
+
+Voxel grid sampling is a method of reducing point cloud data by using the
+`Voxel grids `_ which is regular grids
+in three-dimensional space.
+
+This method determines which each point is in a grid, and replaces the point
+clouds that are in the same Voxel with their average to reduce the number of
+points.
+
+Code Link
+==========
+
+.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.voxel_point_sampling
+
+
+Farthest Point Sampling
+~~~~~~~~~~~~~~~~~~~~~~~~~
+.. figure:: farthest_point_sampling.png
+
+Farthest Point Sampling is a point cloud sampling method by a specified
+number of points so that the distance between points is as far from as
+possible.
+
+This method is useful for machine learning and other situations where
+you want to obtain a specified number of points from point cloud.
+
+API
+=====
+
+.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.farthest_point_sampling
+
+Poisson Disk Sampling
+~~~~~~~~~~~~~~~~~~~~~~~~~
+.. figure:: poisson_disk_sampling.png
+
+Poisson disk sample is a point cloud sampling method by a specified
+number of points so that the algorithm selects points where the distance
+from selected points is greater than a certain distance.
+
+Although this method does not have good performance comparing the Farthest
+distance sample where each point is distributed farther from each other,
+this is suitable for real-time processing because of its fast computation time.
+
+Code Link
+==========
+
+.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.poisson_disk_sampling
+
+
+
diff --git a/docs/modules/3_mapping/point_cloud_sampling/poisson_disk_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/poisson_disk_sampling.png
new file mode 100644
index 0000000000..6863c9e046
Binary files /dev/null and b/docs/modules/3_mapping/point_cloud_sampling/poisson_disk_sampling.png differ
diff --git a/docs/modules/3_mapping/point_cloud_sampling/voxel_point_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/voxel_point_sampling.png
new file mode 100644
index 0000000000..fe1d171f7c
Binary files /dev/null and b/docs/modules/3_mapping/point_cloud_sampling/voxel_point_sampling.png differ
diff --git a/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst b/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst
new file mode 100644
index 0000000000..bee2f64193
--- /dev/null
+++ b/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst
@@ -0,0 +1,11 @@
+Ray casting grid map
+--------------------
+
+This is a 2D ray casting grid mapping example.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: Mapping.ray_casting_grid_map.ray_casting_grid_map.generate_ray_casting_grid_map
diff --git a/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst b/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst
new file mode 100644
index 0000000000..06d85efe61
--- /dev/null
+++ b/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst
@@ -0,0 +1,69 @@
+Object shape recognition using rectangle fitting
+------------------------------------------------
+
+This is an object shape recognition using rectangle fitting.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/rectangle_fitting/animation.gif
+
+This example code is based on this paper algorithm:
+
+- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_
+
+The algorithm consists of 2 steps as below.
+
+Step1: Adaptive range segmentation
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+In the first step, all range data points are segmented into some clusters.
+
+We calculate the distance between each range data and the nearest range data, and if this distance is below a certain threshold, it is judged to be in the same cluster.
+This distance threshold is determined in proportion to the distance from the sensor.
+This is taking advantage of the general model of distance sensors, which tends to have sparser data distribution as the distance from the sensor increases.
+
+The threshold range is calculated by:
+
+.. math:: r_{th} = R_0 + R_d * r_{origin}
+
+where
+
+- :math:`r_{th}`: Threashold range
+- :math:`R_0, R_d`: Constant parameters
+- :math:`r_{origin}`: Distance from the sensor for a range data.
+
+Step2: Rectangle search
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+In the second step, for each cluster calculated in the previous step, rectangular fittings will be applied.
+In this rectangular fitting, each cluster's distance data is rotated at certain angle intervals.
+It is evaluated by one of the three evaluation functions below, then best angle parameter one is selected as the rectangle shape.
+
+1. Rectangle Area Minimization criteria
+=========================================
+
+This evaluation function calculates the area of the smallest rectangle that includes all the points, derived from the difference between the maximum and minimum values on the x-y axis for all distance data points.
+This allows for fitting a rectangle in a direction that encompasses as much of the smallest rectangular shape as possible.
+
+
+2. Closeness criteria
+======================
+
+This evaluation function uses the distances between the top and bottom vertices on the right side of the rectangle and each point in the distance data as evaluation values.
+If there are points on the rectangle edges, this evaluation value decreases.
+
+3. Variance criteria
+=======================
+
+This evaluation function uses the squreed distances between the edges of the rectangle (horizontal and vertical) and each point.
+Calculating the squared error is the same as calculating the variance.
+The smaller this variance, the more it signifies that the points fit within the rectangle.
+
+Code Link
+~~~~~~~~~~~
+
+.. autoclass:: Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting
+ :members:
+
+References
+~~~~~~~~~~
+
+- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_
diff --git a/docs/modules/FastSLAM1_files/FastSLAM1_12_0.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_12_0.png
similarity index 100%
rename from docs/modules/FastSLAM1_files/FastSLAM1_12_0.png
rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_12_0.png
diff --git a/docs/modules/FastSLAM1_files/FastSLAM1_12_1.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_12_1.png
similarity index 100%
rename from docs/modules/FastSLAM1_files/FastSLAM1_12_1.png
rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_12_1.png
diff --git a/docs/modules/FastSLAM1_files/FastSLAM1_1_0.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_1_0.png
similarity index 100%
rename from docs/modules/FastSLAM1_files/FastSLAM1_1_0.png
rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_1_0.png
diff --git a/docs/modules/FastSLAM1.rst b/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst
similarity index 96%
rename from docs/modules/FastSLAM1.rst
rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst
index 052f767489..b6bafa0982 100644
--- a/docs/modules/FastSLAM1.rst
+++ b/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst
@@ -2,16 +2,7 @@
FastSLAM1.0
-----------
-.. code-block:: ipython3
-
- from IPython.display import Image
- Image(filename="animation.png",width=600)
-
-
-
-
-.. image:: FastSLAM1_files/FastSLAM1_1_0.png
- :width: 600px
+.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif
@@ -20,6 +11,9 @@ Simulation
This is a feature based SLAM example using FastSLAM 1.0.
+.. image:: FastSLAM1_1_0.png
+ :width: 600px
+
The blue line is ground truth, the black line is dead reckoning, the red
line is the estimated trajectory with FastSLAM.
@@ -28,10 +22,11 @@ The red points are particles of FastSLAM.
Black points are landmarks, blue crosses are estimated landmark
positions by FastSLAM.
-.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif
- :alt: gif
+Code Link
+~~~~~~~~~~~~
+
+.. autofunction:: SLAM.FastSLAM1.fast_slam1.fast_slam1
- gif
Introduction
~~~~~~~~~~~~
@@ -49,15 +44,15 @@ an array of landmark locations
- The blue line is the true trajectory
- The red line is the estimated trajectory
- The red dots represent the distribution of particles
-- The black line represent dead reckoning tracjectory
+- The black line represent dead reckoning trajectory
- The blue x is the observed and estimated landmarks
- The black x is the true landmark
I.e. Each particle maintains a deterministic pose and n-EKFs for each
landmark and update it with each measurement.
-Algorithm walkthrough
-~~~~~~~~~~~~~~~~~~~~~
+Algorithm walk through
+~~~~~~~~~~~~~~~~~~~~~~~
The particles are initially drawn from a uniform distribution the
represent the initial uncertainty. At each time step we do:
@@ -75,7 +70,7 @@ represent the initial uncertainty. At each time step we do:
The following equations and code snippets we can see how the particles
distribution evolves in case we provide only the control :math:`(v,w)`,
-which are the linear and angular velocity repsectively.
+which are the linear and angular velocity respectively.
:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix} \end{equation*}`
@@ -85,7 +80,7 @@ which are the linear and angular velocity repsectively.
:math:`\begin{equation*} \begin{bmatrix} x_{t+1} \\ y_{t+1} \\ \theta_{t+1} \end{bmatrix}= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\begin{bmatrix} x_{t} \\ y_{t} \\ \theta_{t} \end{bmatrix}+ \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \begin{bmatrix} v_{t} + \sigma_v\\ w_{t} + \sigma_w\\ \end{bmatrix} \end{equation*}`
-The following snippets playsback the recorded trajectory of each
+The following snippets playback the recorded trajectory of each
particle.
To get the insight of the motion model change the value of :math:`R` and
@@ -537,16 +532,13 @@ indices
-.. image:: FastSLAM1_files/FastSLAM1_12_0.png
-
-
-
-.. image:: FastSLAM1_files/FastSLAM1_12_1.png
+.. image:: FastSLAM1_12_0.png
+.. image:: FastSLAM1_12_1.png
References
~~~~~~~~~~
-http://www.probabilistic-robotics.org/
+- `PROBABILISTIC ROBOTICS `_
-http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf
+- `FastSLAM Lecture `_
diff --git a/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst b/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst
new file mode 100644
index 0000000000..59ed3b9f75
--- /dev/null
+++ b/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst
@@ -0,0 +1,22 @@
+FastSLAM 2.0
+------------
+
+This is a feature based SLAM example using FastSLAM 2.0.
+
+The animation has the same meanings as one of FastSLAM 1.0.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif
+
+Code Link
+~~~~~~~~~~~
+
+.. autofunction:: SLAM.FastSLAM2.fast_slam2.fast_slam2
+
+
+References
+~~~~~~~~~~
+
+- `PROBABILISTIC ROBOTICS `_
+
+- `SLAM simulations by Tim Bailey `_
+
diff --git a/SLAM/EKFSLAM/animation.png b/docs/modules/4_slam/ekf_slam/ekf_slam_1_0.png
similarity index 100%
rename from SLAM/EKFSLAM/animation.png
rename to docs/modules/4_slam/ekf_slam/ekf_slam_1_0.png
diff --git a/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst
new file mode 100644
index 0000000000..3967a7ae4d
--- /dev/null
+++ b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst
@@ -0,0 +1,590 @@
+EKF SLAM
+--------
+
+This is an Extended Kalman Filter based SLAM example.
+
+The blue line is ground truth, the black line is dead reckoning, the red
+line is the estimated trajectory with EKF SLAM.
+
+The green crosses are estimated landmarks.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif
+
+Simulation
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+This is a simulation of EKF SLAM.
+
+- Black stars: landmarks
+- Green crosses: estimates of landmark positions
+- Black line: dead reckoning
+- Blue line: ground truth
+- Red line: EKF SLAM position estimation
+
+Code Link
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. autofunction:: SLAM.EKFSLAM.ekf_slam.ekf_slam
+
+
+Introduction
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+EKF SLAM models the SLAM problem in a single EKF where the modeled state
+is both the pose :math:`(x, y, \theta)` and an array of landmarks
+:math:`[(x_1, y_1), (x_2, x_y), ... , (x_n, y_n)]` for :math:`n`
+landmarks. The covariance between each of the positions and landmarks
+are also tracked.
+
+:math:`\begin{equation} X = \begin{bmatrix} x \\ y \\ \theta \\ x_1 \\ y_1 \\ x_2 \\ y_2 \\ \dots \\ x_n \\ y_n \end{bmatrix} \end{equation}`
+
+:math:`\begin{equation} P = \begin{bmatrix} \sigma_{xx} & \sigma_{xy} & \sigma_{x\theta} & \sigma_{xx_1} & \sigma_{xy_1} & \sigma_{xx_2} & \sigma_{xy_2} & \dots & \sigma_{xx_n} & \sigma_{xy_n} \\ \sigma_{yx} & \sigma_{yy} & \sigma_{y\theta} & \sigma_{yx_1} & \sigma_{yy_1} & \sigma_{yx_2} & \sigma_{yy_2} & \dots & \sigma_{yx_n} & \sigma_{yy_n} \\ & & & & \vdots & & & & & \\ \sigma_{x_nx} & \sigma_{x_ny} & \sigma_{x_n\theta} & \sigma_{x_nx_1} & \sigma_{x_ny_1} & \sigma_{x_nx_2} & \sigma_{x_ny_2} & \dots & \sigma_{x_nx_n} & \sigma_{x_ny_n} \end{bmatrix} \end{equation}`
+
+A single estimate of the pose is tracked over time, while the confidence
+in the pose is tracked by the covariance matrix :math:`P`. :math:`P` is
+a symmetric square matrix which each element in the matrix corresponding
+to the covariance between two parts of the system. For example,
+:math:`\sigma_{xy}` represents the covariance between the belief of
+:math:`x` and :math:`y` and is equal to :math:`\sigma_{yx}`.
+
+The state can be represented more concisely as follows.
+
+:math:`\begin{equation} X = \begin{bmatrix} x \\ m \end{bmatrix} \end{equation}`
+:math:`\begin{equation} P = \begin{bmatrix} \Sigma_{xx} & \Sigma_{xm}\\ \Sigma_{mx} & \Sigma_{mm}\\ \end{bmatrix} \end{equation}`
+
+Here the state simplifies to a combination of pose (:math:`x`) and map
+(:math:`m`). The covariance matrix becomes easier to understand and
+simply reads as the uncertainty of the robots pose
+(:math:`\Sigma_{xx}`), the uncertainty of the map (:math:`\Sigma_{mm}`),
+and the uncertainty of the robots pose with respect to the map and vice
+versa (:math:`\Sigma_{xm}`, :math:`\Sigma_{mx}`).
+
+Take care to note the difference between :math:`X` (state) and :math:`x`
+(pose).
+
+.. code:: ipython3
+
+ """
+ Extended Kalman Filter SLAM example
+ original author: Atsushi Sakai (@Atsushi_twi)
+ notebook author: Andrew Tu (drewtu2)
+ """
+
+ import math
+ import numpy as np
+ %matplotlib notebook
+ import matplotlib.pyplot as plt
+
+
+ # EKF state covariance
+ Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2 # Change in covariance
+
+ # Simulation parameter
+ Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 # Sensor Noise
+ Rsim = np.diag([1.0, np.deg2rad(10.0)])**2 # Process Noise
+
+ DT = 0.1 # time tick [s]
+ SIM_TIME = 50.0 # simulation time [s]
+ MAX_RANGE = 20.0 # maximum observation range
+ M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.
+ STATE_SIZE = 3 # State size [x,y,yaw]
+ LM_SIZE = 2 # LM state size [x,y]
+
+ show_animation = True
+
+Algorithm Walk through
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+At each time step, the following is done. - predict the new state using
+the control functions - update the belief in landmark positions based on
+the estimated state and measurements
+
+.. code:: ipython3
+
+ def ekf_slam(xEst, PEst, u, z):
+ """
+ Performs an iteration of EKF SLAM from the available information.
+
+ :param xEst: the belief in last position
+ :param PEst: the uncertainty in last position
+ :param u: the control function applied to the last position
+ :param z: measurements at this step
+ :returns: the next estimated position and associated covariance
+ """
+
+ # Predict
+ xEst, PEst = predict(xEst, PEst, u)
+ initP = np.eye(2)
+
+ # Update
+ xEst, PEst = update(xEst, PEst, z, initP)
+
+ return xEst, PEst
+
+
+1- Predict
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+**Predict State update:** The following equations describe the predicted
+motion model of the robot in case we provide only the control
+:math:`(v,w)`, which are the linear and angular velocity respectively.
+
+:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} B= \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} U= \begin{bmatrix} v_t\\ w_t\\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} X = FX + BU \end{equation*}`
+
+:math:`\begin{equation*} \begin{bmatrix} x_{t+1} \\ y_{t+1} \\ \theta_{t+1} \end{bmatrix}= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\begin{bmatrix} x_{t} \\ y_{t} \\ \theta_{t} \end{bmatrix}+ \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \begin{bmatrix} v_{t} + \sigma_v\\ w_{t} + \sigma_w\\ \end{bmatrix} \end{equation*}`
+
+Notice that while :math:`U` is only defined by :math:`v_t` and
+:math:`w_t`, in the actual calculations, a :math:`+\sigma_v` and
+:math:`+\sigma_w` appear. These values represent the error between the
+given control inputs and the actual control inputs.
+
+As a result, the simulation is set up as the following. :math:`R`
+represents the process noise which is added to the control inputs to
+simulate noise experienced in the real world. A set of truth values are
+computed from the raw control values while the values dead reckoning
+values incorporate the error into the estimation.
+
+:math:`\begin{equation*} R= \begin{bmatrix} \sigma_v\\ \sigma_w\\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} X_{true} = FX + B(U) \end{equation*}`
+
+:math:`\begin{equation*} X_{DR} = FX + B(U + R) \end{equation*}`
+
+The implementation of the motion model prediction code is shown in
+``motion_model``. The ``observation`` function shows how the simulation
+uses (or doesn’t use) the process noise ``Rsim`` to the find the ground
+truth and dead reckoning estimates of the pose.
+
+**Predict covariance:** Add the state covariance to the the current
+uncertainty of the EKF. At each time step, the uncertainty in the system
+grows by the covariance of the pose, :math:`Cx`.
+
+:math:`P = G^TPG + Cx`
+
+Notice this uncertainty is only growing with respect to the pose, not
+the landmarks.
+
+.. code:: ipython3
+
+ def predict(xEst, PEst, u):
+ """
+ Performs the prediction step of EKF SLAM
+
+ :param xEst: nx1 state vector
+ :param PEst: nxn covariance matrix
+ :param u: 2x1 control vector
+ :returns: predicted state vector, predicted covariance, jacobian of control vector, transition fx
+ """
+ G, Fx = jacob_motion(xEst, u)
+ xEst[0:STATE_SIZE] = motion_model(xEst[0:STATE_SIZE], u)
+ # Fx is an an identity matrix of size (STATE_SIZE)
+ # sigma = G*sigma*G.T + Noise
+ PEst = G.T @ PEst @ G + Fx.T @ Cx @ Fx
+ return xEst, PEst
+
+.. code:: ipython3
+
+ def motion_model(x, u):
+ """
+ Computes the motion model based on current state and input function.
+
+ :param x: 3x1 pose estimation
+ :param u: 2x1 control input [v; w]
+ :returns: the resulting state after the control function is applied
+ """
+ F = np.array([[1.0, 0, 0],
+ [0, 1.0, 0],
+ [0, 0, 1.0]])
+
+ B = np.array([[DT * math.cos(x[2, 0]), 0],
+ [DT * math.sin(x[2, 0]), 0],
+ [0.0, DT]])
+
+ x = (F @ x) + (B @ u)
+ return x
+
+2 - Update
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+In the update phase, the observations of nearby landmarks are used to
+correct the location estimate.
+
+For every landmark observed, it is associated to a particular landmark
+in the known map. If no landmark exists in the position surrounding the
+landmark, it is taken as a NEW landmark. The distance threshold for how
+far a landmark must be from the next known landmark before its
+considered to be a new landmark is set by ``M_DIST_TH``.
+
+With an observation associated to the appropriate landmark, the
+**innovation** can be calculated. Innovation (:math:`y`) is the
+difference between the observation and the observation that *should*
+have been made if the observation were made from the pose predicted in
+the predict stage.
+
+:math:`y = z_t - h(X)`
+
+With the innovation calculated, the question becomes which to trust more
+- the observations or the predictions? To determine this, we calculate
+the Kalman Gain - a percent of how much of the innovation to add to the
+prediction based on the uncertainty in the predict step and the update
+step.
+
+:math:`K = \bar{P_t}H_t^T(H_t\bar{P_t}H_t^T + Q_t)^{-1}`
+In these equations, :math:`H` is the jacobian of the
+measurement function. The multiplications by :math:`H^T` and :math:`H`
+represent the application of the delta to the measurement covariance.
+Intuitively, this equation is applying the following from the single
+variate Kalman equation but in the multivariate form, i.e. finding the
+ratio of the uncertainty of the process compared the measurement.
+
+K = :math:`\frac{\bar{P_t}}{\bar{P_t} + Q_t}`
+
+If :math:`Q_t << \bar{P_t}`, (i.e. the measurement covariance is low
+relative to the current estimate), then the Kalman gain will be
+:math:`~1`. This results in adding all of the innovation to the estimate
+– and therefore completely believing the measurement.
+
+However, if :math:`Q_t >> \bar{P_t}` then the Kalman gain will go to 0,
+signaling a high trust in the process and little trust in the
+measurement.
+
+The update is captured in the following.
+
+:math:`xUpdate = xEst + (K * y)`
+
+Of course, the covariance must also be updated as well to account for
+the changing uncertainty.
+
+:math:`P_{t} = (I-K_tH_t)\bar{P_t}`
+
+.. code:: ipython3
+
+ def update(xEst, PEst, z, initP):
+ """
+ Performs the update step of EKF SLAM
+
+ :param xEst: nx1 the predicted pose of the system and the pose of the landmarks
+ :param PEst: nxn the predicted covariance
+ :param z: the measurements read at new position
+ :param initP: 2x2 an identity matrix acting as the initial covariance
+ :returns: the updated state and covariance for the system
+ """
+ for iz in range(len(z[:, 0])): # for each observation
+ minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) # associate to a known landmark
+
+ nLM = calc_n_LM(xEst) # number of landmarks we currently know about
+
+ if minid == nLM: # Landmark is a NEW landmark
+ print("New LM")
+ # Extend state and covariance matrix
+ xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :])))
+ PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),
+ np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))
+ xEst = xAug
+ PEst = PAug
+
+ lm = get_LM_Pos_from_state(xEst, minid)
+ y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid)
+
+ K = (PEst @ H.T) @ np.linalg.inv(S) # Calculate Kalman Gain
+ xEst = xEst + (K @ y)
+ PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst
+
+ xEst[2] = pi_2_pi(xEst[2])
+ return xEst, PEst
+
+
+.. code:: ipython3
+
+ def calc_innovation(lm, xEst, PEst, z, LMid):
+ """
+ Calculates the innovation based on expected position and landmark position
+
+ :param lm: landmark position
+ :param xEst: estimated position/state
+ :param PEst: estimated covariance
+ :param z: read measurements
+ :param LMid: landmark id
+ :returns: returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain
+ """
+ delta = lm - xEst[0:2]
+ q = (delta.T @ delta)[0, 0]
+ zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]
+ zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]])
+ # zp is the expected measurement based on xEst and the expected landmark position
+
+ y = (z - zp).T # y = innovation
+ y[1] = pi_2_pi(y[1])
+
+ H = jacobH(q, delta, xEst, LMid + 1)
+ S = H @ PEst @ H.T + Cx[0:2, 0:2]
+
+ return y, S, H
+
+ def jacobH(q, delta, x, i):
+ """
+ Calculates the jacobian of the measurement function
+
+ :param q: the range from the system pose to the landmark
+ :param delta: the difference between a landmark position and the estimated system position
+ :param x: the state, including the estimated system position
+ :param i: landmark id + 1
+ :returns: the jacobian H
+ """
+ sq = math.sqrt(q)
+ G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],
+ [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]])
+
+ G = G / q
+ nLM = calc_n_LM(x)
+ F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
+ F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),
+ np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
+
+ F = np.vstack((F1, F2))
+
+ H = G @ F
+
+ return H
+
+Observation Step
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The observation step described here is outside the main EKF SLAM process
+and is primarily used as a method of driving the simulation. The
+observations function is in charge of calculating how the poses of the
+robots change and accumulate error over time, and the theoretical
+measurements that are expected as a result of each measurement.
+
+Observations are based on the TRUE position of the robot. Error in dead
+reckoning and control functions are passed along here as well.
+
+.. code:: ipython3
+
+ def observation(xTrue, xd, u, RFID):
+ """
+ :param xTrue: the true pose of the system
+ :param xd: the current noisy estimate of the system
+ :param u: the current control input
+ :param RFID: the true position of the landmarks
+
+ :returns: Computes the true position, observations, dead reckoning (noisy) position,
+ and noisy control function
+ """
+ xTrue = motion_model(xTrue, u)
+
+ # add noise to gps x-y
+ z = np.zeros((0, 3))
+
+ for i in range(len(RFID[:, 0])): # Test all beacons, only add the ones we can see (within MAX_RANGE)
+
+ dx = RFID[i, 0] - xTrue[0, 0]
+ dy = RFID[i, 1] - xTrue[1, 0]
+ d = math.sqrt(dx**2 + dy**2)
+ angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
+ if d <= MAX_RANGE:
+ dn = d + np.random.randn() * Qsim[0, 0] # add noise
+ anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
+ zi = np.array([dn, anglen, i])
+ z = np.vstack((z, zi))
+
+ # add noise to input
+ ud = np.array([[
+ u[0, 0] + np.random.randn() * Rsim[0, 0],
+ u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T
+
+ xd = motion_model(xd, ud)
+ return xTrue, z, xd, ud
+
+.. code:: ipython3
+
+ def calc_n_LM(x):
+ """
+ Calculates the number of landmarks currently tracked in the state
+ :param x: the state
+ :returns: the number of landmarks n
+ """
+ n = int((len(x) - STATE_SIZE) / LM_SIZE)
+ return n
+
+
+ def jacob_motion(x, u):
+ """
+ Calculates the jacobian of motion model.
+
+ :param x: The state, including the estimated position of the system
+ :param u: The control function
+ :returns: G: Jacobian
+ Fx: STATE_SIZE x (STATE_SIZE + 2 * num_landmarks) matrix where the left side is an identity matrix
+ """
+
+ # [eye(3) [0 x y; 0 x y; 0 x y]]
+ Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(
+ (STATE_SIZE, LM_SIZE * calc_n_LM(x)))))
+
+ jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],
+ [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],
+ [0.0, 0.0, 0.0]],dtype=object)
+
+ G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx
+ if calc_n_LM(x) > 0:
+ print(Fx.shape)
+ return G, Fx,
+
+
+.. code:: ipython3
+
+ def calc_LM_Pos(x, z):
+ """
+ Calculates the pose in the world coordinate frame of a landmark at the given measurement.
+
+ :param x: [x; y; theta]
+ :param z: [range; bearing]
+ :returns: [x; y] for given measurement
+ """
+ zp = np.zeros((2, 1))
+
+ zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1])
+ zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1])
+ #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])
+ #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])
+
+ return zp
+
+
+ def get_LM_Pos_from_state(x, ind):
+ """
+ Returns the position of a given landmark
+
+ :param x: The state containing all landmark positions
+ :param ind: landmark id
+ :returns: The position of the landmark
+ """
+ lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]
+
+ return lm
+
+
+ def search_correspond_LM_ID(xAug, PAug, zi):
+ """
+ Landmark association with Mahalanobis distance.
+
+ If this landmark is at least M_DIST_TH units away from all known landmarks,
+ it is a NEW landmark.
+
+ :param xAug: The estimated state
+ :param PAug: The estimated covariance
+ :param zi: the read measurements of specific landmark
+ :returns: landmark id
+ """
+
+ nLM = calc_n_LM(xAug)
+
+ mdist = []
+
+ for i in range(nLM):
+ lm = get_LM_Pos_from_state(xAug, i)
+ y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
+ mdist.append(y.T @ np.linalg.inv(S) @ y)
+
+ mdist.append(M_DIST_TH) # new landmark
+
+ minid = mdist.index(min(mdist))
+
+ return minid
+
+ def calc_input():
+ v = 1.0 # [m/s]
+ yawrate = 0.1 # [rad/s]
+ u = np.array([[v, yawrate]]).T
+ return u
+
+ def pi_2_pi(angle):
+ return (angle + math.pi) % (2 * math.pi) - math.pi
+
+.. code:: ipython3
+
+ def main():
+ print(" start!!")
+
+ time = 0.0
+
+ # RFID positions [x, y]
+ RFID = np.array([[10.0, -2.0],
+ [15.0, 10.0],
+ [3.0, 15.0],
+ [-5.0, 20.0]])
+
+ # State Vector [x y yaw v]'
+ xEst = np.zeros((STATE_SIZE, 1))
+ xTrue = np.zeros((STATE_SIZE, 1))
+ PEst = np.eye(STATE_SIZE)
+
+ xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning
+
+ # history
+ hxEst = xEst
+ hxTrue = xTrue
+ hxDR = xTrue
+
+ while SIM_TIME >= time:
+ time += DT
+ u = calc_input()
+
+ xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+
+ xEst, PEst = ekf_slam(xEst, PEst, ud, z)
+
+ x_state = xEst[0:STATE_SIZE]
+
+ # store data history
+ hxEst = np.hstack((hxEst, x_state))
+ hxDR = np.hstack((hxDR, xDR))
+ hxTrue = np.hstack((hxTrue, xTrue))
+
+ if show_animation: # pragma: no cover
+ plt.cla()
+
+ plt.plot(RFID[:, 0], RFID[:, 1], "*k")
+ plt.plot(xEst[0], xEst[1], ".r")
+
+ # plot landmark
+ for i in range(calc_n_LM(xEst)):
+ plt.plot(xEst[STATE_SIZE + i * 2],
+ xEst[STATE_SIZE + i * 2 + 1], "xg")
+
+ plt.plot(hxTrue[0, :],
+ hxTrue[1, :], "-b")
+ plt.plot(hxDR[0, :],
+ hxDR[1, :], "-k")
+ plt.plot(hxEst[0, :],
+ hxEst[1, :], "-r")
+ plt.axis("equal")
+ plt.grid(True)
+ plt.pause(0.001)
+
+.. code:: ipython3
+
+ %matplotlib notebook
+ main()
+
+
+.. parsed-literal::
+
+ start!!
+ New LM
+ New LM
+ New LM
+
+.. image:: ekf_slam_1_0.png
+
+Reference
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+- `PROBABILISTIC ROBOTICS `_
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst
new file mode 100644
index 0000000000..15963aff79
--- /dev/null
+++ b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst
@@ -0,0 +1,208 @@
+Graph SLAM for a real-world SE(2) dataset
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. code:: ipython3
+
+ from graphslam.graph import Graph
+ from graphslam.load import load_g2o_se2
+
+Introduction
+^^^^^^^^^^^^
+
+For a complete derivation of the Graph SLAM algorithm, please see
+`Graph SLAM Formulation`_.
+
+This notebook illustrates the iterative optimization of a real-world
+:math:`SE(2)` dataset. The code can be found in the ``graphslam``
+folder. For simplicity, numerical differentiation is used in lieu of
+analytic Jacobians. This code originated from the
+`python-graphslam `__
+repo, which is a full-featured Graph SLAM solver. The dataset in this
+example is used with permission from Luca Carlone and was downloaded
+from his `website `__.
+
+The Dataset
+^^^^^^^^^^^^
+
+.. code:: ipython3
+
+ g = load_g2o_se2("data/input_INTEL.g2o")
+
+ print("Number of edges: {}".format(len(g._edges)))
+ print("Number of vertices: {}".format(len(g._vertices)))
+
+
+.. parsed-literal::
+
+ Number of edges: 1483
+ Number of vertices: 1228
+
+
+.. code:: ipython3
+
+ g.plot(title=r"Original ($\chi^2 = {:.0f}$)".format(g.calc_chi2()))
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png
+
+
+Each edge in this dataset is a constraint that compares the measured
+:math:`SE(2)` transformation between two poses to the expected
+:math:`SE(2)` transformation between them, as computed using the current
+pose estimates. These edges can be classified into two categories:
+
+1. Odometry edges constrain two consecutive vertices, and the
+ measurement for the :math:`SE(2)` transformation comes directly from
+ odometry data.
+2. Scan-matching edges constrain two non-consecutive vertices. These
+ scan matches can be computed using, for example, 2-D LiDAR data or
+ landmarks; the details of how these constraints are determined is
+ beyond the scope of this example. This is often referred to as *loop
+ closure* in the Graph SLAM literature.
+
+We can easily parse out the two different types of edges present in this
+dataset and plot them.
+
+.. code:: ipython3
+
+ def parse_edges(g):
+ """Split the graph `g` into two graphs, one with only odometry edges and the other with only scan-matching edges.
+
+ Parameters
+ ----------
+ g : graphslam.graph.Graph
+ The input graph
+
+ Returns
+ -------
+ g_odom : graphslam.graph.Graph
+ A graph consisting of the vertices and odometry edges from `g`
+ g_scan : graphslam.graph.Graph
+ A graph consisting of the vertices and scan-matching edges from `g`
+
+ """
+ edges_odom = []
+ edges_scan = []
+
+ for e in g._edges:
+ if abs(e.vertex_ids[1] - e.vertex_ids[0]) == 1:
+ edges_odom.append(e)
+ else:
+ edges_scan.append(e)
+
+ g_odom = Graph(edges_odom, g._vertices)
+ g_scan = Graph(edges_scan, g._vertices)
+
+ return g_odom, g_scan
+
+.. code:: ipython3
+
+ g_odom, g_scan = parse_edges(g)
+
+ print("Number of odometry edges: {:4d}".format(len(g_odom._edges)))
+ print("Number of scan-matching edges: {:4d}".format(len(g_scan._edges)))
+
+ print("\nχ^2 error from odometry edges: {:11.3f}".format(g_odom.calc_chi2()))
+ print("χ^2 error from scan-matching edges: {:11.3f}".format(g_scan.calc_chi2()))
+
+
+.. parsed-literal::
+
+ Number of odometry edges: 1227
+ Number of scan-matching edges: 256
+
+ χ^2 error from odometry edges: 0.232
+ χ^2 error from scan-matching edges: 7191686.151
+
+
+.. code:: ipython3
+
+ g_odom.plot(title="Odometry edges")
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png
+
+
+.. code:: ipython3
+
+ g_scan.plot(title="Scan-matching edges")
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png
+
+
+Optimization
+^^^^^^^^^^^^
+
+Initially, the pose estimates are consistent with the collected odometry
+measurements, and the odometry edges contribute almost zero towards the
+:math:`\chi^2` error. However, there are large discrepancies between the
+scan-matching constraints and the initial pose estimates. This is not
+surprising, since small errors in odometry readings that are propagated
+over time can lead to large errors in the robot’s trajectory. What makes
+Graph SLAM effective is that it allows incorporation of multiple
+different data sources into a single optimization problem.
+
+.. code:: ipython3
+
+ g.optimize()
+
+
+.. parsed-literal::
+
+
+ Iteration chi^2 rel. change
+ --------- ----- -----------
+ 0 7191686.3825
+ 1 320031728.8624 43.500234
+ 2 125083004.3299 -0.609154
+ 3 338155.9074 -0.997297
+ 4 735.1344 -0.997826
+ 5 215.8405 -0.706393
+ 6 215.8405 -0.000000
+
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/Graph_SLAM_optimization.gif
+
+.. code:: ipython3
+
+ g.plot(title="Optimized")
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png
+
+
+.. code:: ipython3
+
+ print("\nχ^2 error from odometry edges: {:7.3f}".format(g_odom.calc_chi2()))
+ print("χ^2 error from scan-matching edges: {:7.3f}".format(g_scan.calc_chi2()))
+
+
+.. parsed-literal::
+
+
+ χ^2 error from odometry edges: 142.189
+ χ^2 error from scan-matching edges: 73.652
+
+
+.. code:: ipython3
+
+ g_odom.plot(title="Odometry edges")
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png
+
+
+.. code:: ipython3
+
+ g_scan.plot(title="Scan-matching edges")
+
+
+
+.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png
+
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png
new file mode 100644
index 0000000000..a3fca366e4
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png
new file mode 100644
index 0000000000..7a3a161299
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png
new file mode 100644
index 0000000000..3684e79652
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png
new file mode 100644
index 0000000000..a24bd005d9
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png
new file mode 100644
index 0000000000..018ca9d92b
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png
new file mode 100644
index 0000000000..f29e4d9206
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc.rst b/docs/modules/4_slam/graph_slam/graphSLAM_doc.rst
new file mode 100644
index 0000000000..5297604809
--- /dev/null
+++ b/docs/modules/4_slam/graph_slam/graphSLAM_doc.rst
@@ -0,0 +1,554 @@
+
+Graph SLAM
+~~~~~~~~~~~~
+
+.. code:: ipython3
+
+ import copy
+ import math
+ import itertools
+ import numpy as np
+ import matplotlib.pyplot as plt
+ from graph_based_slam import calc_rotational_matrix, calc_jacobian, cal_observation_sigma, \
+ calc_input, observation, motion_model, Edge, pi_2_pi
+
+ %matplotlib inline
+ np.set_printoptions(precision=3, suppress=True)
+ np.random.seed(0)
+
+Introduction
+^^^^^^^^^^^^
+
+In contrast to the probabilistic approaches for solving SLAM, such as
+EKF, UKF, particle filters, and so on, the graph technique formulates
+the SLAM as an optimization problem. It is mostly used to solve the full
+SLAM problem in an offline fashion, i.e. optimize all the poses of the
+robot after the path has been traversed. However, some variants are
+available that uses graph-based approaches to perform online estimation
+or to solve for a subset of the poses.
+
+GraphSLAM uses the motion information as well as the observations of the
+environment to create least square problem that can be solved using
+standard optimization techniques.
+
+Minimal Example
+^^^^^^^^^^^^^^^
+
+The following example illustrates the main idea behind graphSLAM. A
+simple case of a 1D robot is considered that can only move in 1
+direction. The robot is commanded to move forward with a control input
+:math:`u_t=1`, however, the motion is not perfect and the measured
+odometry will deviate from the true path. At each time step the robot can
+observe its environment, for this simple case as well, there is only a
+single landmark at coordinates :math:`x=3`. The measured observations
+are the range between the robot and landmark. These measurements are
+also subjected to noise. No bearing information is required since this
+is a 1D problem.
+
+To solve this, graphSLAM creates what is called as the system
+information matrix :math:`\Omega` also referred to as :math:`H` and the
+information vector :math:`\xi` also known as :math:`b`. The entries are
+created based on the information of the motion and the observation.
+
+.. code:: ipython3
+
+ R = 0.2
+ Q = 0.2
+ N = 3
+ graphics_radius = 0.1
+
+ odom = np.empty((N,1))
+ obs = np.empty((N,1))
+ x_true = np.empty((N,1))
+
+ landmark = 3
+ # Simulated readings of odometry and observations
+ x_true[0], odom[0], obs[0] = 0.0, 0.0, 2.9
+ x_true[1], odom[1], obs[1] = 1.0, 1.5, 2.0
+ x_true[2], odom[2], obs[2] = 2.0, 2.4, 1.0
+
+ hxDR = copy.deepcopy(odom)
+ # Visualization
+ plt.plot(landmark,0, '*k', markersize=30)
+ for i in range(N):
+ plt.plot(odom[i], 0, '.', markersize=50, alpha=0.8, color='steelblue')
+ plt.plot([odom[i], odom[i] + graphics_radius],
+ [0,0], 'r')
+ plt.text(odom[i], 0.02, "X_{}".format(i), fontsize=12)
+ plt.plot(obs[i]+odom[i],0,'.', markersize=25, color='brown')
+ plt.plot(x_true[i],0,'.g', markersize=20)
+ plt.grid()
+ plt.show()
+
+
+ # Defined as a function to facilitate iteration
+ def get_H_b(odom, obs):
+ """
+ Create the information matrix and information vector. This implementation is
+ based on the concept of virtual measurement i.e. the observations of the
+ landmarks are converted into constraints (edges) between the nodes that
+ have observed this landmark.
+ """
+ measure_constraints = {}
+ omegas = {}
+ zids = list(itertools.combinations(range(N),2))
+ H = np.zeros((N,N))
+ b = np.zeros((N,1))
+ for (t1, t2) in zids:
+ x1 = odom[t1]
+ x2 = odom[t2]
+ z1 = obs[t1]
+ z2 = obs[t2]
+
+ # Adding virtual measurement constraint
+ measure_constraints[(t1,t2)] = (x2-x1-z1+z2)
+ omegas[(t1,t2)] = (1 / (2*Q))
+
+ # populate system's information matrix and vector
+ H[t1,t1] += omegas[(t1,t2)]
+ H[t2,t2] += omegas[(t1,t2)]
+ H[t2,t1] -= omegas[(t1,t2)]
+ H[t1,t2] -= omegas[(t1,t2)]
+
+ b[t1] += omegas[(t1,t2)] * measure_constraints[(t1,t2)]
+ b[t2] -= omegas[(t1,t2)] * measure_constraints[(t1,t2)]
+
+ return H, b
+
+
+ H, b = get_H_b(odom, obs)
+ print("The determinant of H: ", np.linalg.det(H))
+ H[0,0] += 1 # np.inf ?
+ print("The determinant of H after anchoring constraint: ", np.linalg.det(H))
+
+ for i in range(5):
+ H, b = get_H_b(odom, obs)
+ H[(0,0)] += 1
+
+ # Recover the posterior over the path
+ dx = np.linalg.inv(H) @ b
+ odom += dx
+ # repeat till convergence
+ print("Running graphSLAM ...")
+ print("Odometry values after optimzation: \n", odom)
+
+ plt.figure()
+ plt.plot(x_true, np.zeros(x_true.shape), '.', markersize=20, label='Ground truth')
+ plt.plot(odom, np.zeros(x_true.shape), '.', markersize=20, label='Estimation')
+ plt.plot(hxDR, np.zeros(x_true.shape), '.', markersize=20, label='Odom')
+ plt.legend()
+ plt.grid()
+ plt.show()
+
+
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_2_0.png
+
+
+.. parsed-literal::
+
+ The determinant of H: 0.0
+ The determinant of H after anchoring constraint: 18.750000000000007
+ Running graphSLAM ...
+ Odometry values after optimzation:
+ [[-0. ]
+ [ 0.9]
+ [ 1.9]]
+
+
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_2_2.png
+
+
+In particular, the tasks are split into 2 parts, graph construction, and
+graph optimization. ### Graph Construction
+
+Firstly the nodes are defined
+:math:`\boldsymbol{x} = \boldsymbol{x}_{1:n}` such that each node is the
+pose of the robot at time :math:`t_i` Secondly, the edges i.e. the
+constraints, are constructed according to the following conditions:
+
+- robot moves from :math:`\boldsymbol{x}_i` to
+ :math:`\boldsymbol{x}_j`. This edge corresponds to the odometry
+ measurement. Relative motion constraints (Not included in the
+ previous minimal example).
+- Measurement constraints, this can be done in two ways:
+
+ - The information matrix is set in such a way that it includes the
+ landmarks in the map as well. Then the constraints can be entered
+ in a straightforward fashion between a node
+ :math:`\boldsymbol{x}_i` and some landmark :math:`m_k`
+ - Through creating a virtual measurement among all the node that
+ have observed the same landmark. More concretely, robot observes
+ the same landmark from :math:`\boldsymbol{x}_i` and
+ :math:`\boldsymbol{x}_j`. Relative measurement constraint. The
+ “virtual measurement” :math:`\boldsymbol{z}_{ij}`, which is the
+ estimated pose of :math:`\boldsymbol{x}_j` as seen from the node
+ :math:`\boldsymbol{x}_i`. The virtual measurement can then be
+ entered in the information matrix and vector in a similar fashion
+ to the motion constraints.
+
+An edge is fully characterized by the values of the error (entry to
+information vector) and the local information matrix (entry to the
+system’s information vector). The larger the local information matrix
+(lower :math:`Q` or :math:`R`) the values that this edge will contribute
+with.
+
+Important Notes:
+
+- The addition to the information matrix and vector are added to the
+ earlier values.
+- In the case of 2D robot, the constraints will be non-linear,
+ therefore, a Jacobian of the error w.r.t the states is needed when
+ updated :math:`H` and :math:`b`.
+- The anchoring constraint is needed in order to avoid having a
+ singular information matri.
+
+Graph Optimization
+^^^^^^^^^^^^^^^^^^
+
+The result from this formulation yields an overdetermined system of
+equations. The goal after constructing the graph is to find:
+:math:`x^*=\underset{x}{\mathrm{argmin}}~\underset{ij}\Sigma~f(e_{ij})`,
+where :math:`f` is some error function that depends on the edges between
+to related nodes :math:`i` and :math:`j`. The derivation in the references
+arrive at the solution for :math:`x^* = H^{-1}b`
+
+Planar Example:
+^^^^^^^^^^^^^^^
+
+Now we will go through an example with a more realistic case of a 2D
+robot with 3DoF, namely, :math:`[x, y, \theta]^T`
+
+.. code:: ipython3
+
+ # Simulation parameter
+ Qsim = np.diag([0.01, np.deg2rad(0.010)])**2 # error added to range and bearing
+ Rsim = np.diag([0.1, np.deg2rad(1.0)])**2 # error added to [v, w]
+
+ DT = 2.0 # time tick [s]
+ SIM_TIME = 100.0 # simulation time [s]
+ MAX_RANGE = 30.0 # maximum observation range
+ STATE_SIZE = 3 # State size [x,y,yaw]
+
+ # TODO: Why not use Qsim ?
+ # Covariance parameter of Graph Based SLAM
+ C_SIGMA1 = 0.1
+ C_SIGMA2 = 0.1
+ C_SIGMA3 = np.deg2rad(1.0)
+
+ MAX_ITR = 20 # Maximum iteration during optimization
+ timesteps = 1
+
+ # consider only 2 landmarks for simplicity
+ # RFID positions [x, y, yaw]
+ RFID = np.array([[10.0, -2.0, 0.0],
+ # [15.0, 10.0, 0.0],
+ # [3.0, 15.0, 0.0],
+ # [-5.0, 20.0, 0.0],
+ # [-5.0, 5.0, 0.0]
+ ])
+
+ # State Vector [x y yaw v]'
+ xTrue = np.zeros((STATE_SIZE, 1))
+ xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning
+ xTrue[2] = np.deg2rad(45)
+ xDR[2] = np.deg2rad(45)
+ # history initial values
+ hxTrue = xTrue
+ hxDR = xTrue
+ _, z, _, _ = observation(xTrue, xDR, np.array([[0,0]]).T, RFID)
+ hz = [z]
+
+ for i in range(timesteps):
+ u = calc_input()
+ xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
+ hxDR = np.hstack((hxDR, xDR))
+ hxTrue = np.hstack((hxTrue, xTrue))
+ hz.append(z)
+
+ # visualize
+ graphics_radius = 0.3
+ plt.plot(RFID[:, 0], RFID[:, 1], "*k", markersize=20)
+ plt.plot(hxDR[0, :], hxDR[1, :], '.', markersize=50, alpha=0.8, label='Odom')
+ plt.plot(hxTrue[0, :], hxTrue[1, :], '.', markersize=20, alpha=0.6, label='X_true')
+
+ for i in range(hxDR.shape[1]):
+ x = hxDR[0, i]
+ y = hxDR[1, i]
+ yaw = hxDR[2, i]
+ plt.plot([x, x + graphics_radius * np.cos(yaw)],
+ [y, y + graphics_radius * np.sin(yaw)], 'r')
+ d = hz[i][:, 0]
+ angle = hz[i][:, 1]
+ plt.plot([x + d * np.cos(angle + yaw)], [y + d * np.sin(angle + yaw)], '.',
+ markersize=20, alpha=0.7)
+ plt.legend()
+ plt.grid()
+ plt.show()
+
+
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_4_0.png
+
+
+.. code:: ipython3
+
+ # Copy the data to have a consistent naming with the .py file
+ zlist = copy.deepcopy(hz)
+ x_opt = copy.deepcopy(hxDR)
+ xlist = copy.deepcopy(hxDR)
+ number_of_nodes = x_opt.shape[1]
+ n = number_of_nodes * STATE_SIZE
+
+After the data has been saved, the graph will be constructed by looking
+at each pair for nodes. The virtual measurement is only created if two
+nodes have observed the same landmark at different points in time. The
+next cells are a walk through for a single iteration of graph
+construction -> optimization -> estimate update.
+
+.. code:: ipython3
+
+ # get all the possible combination of the different node
+ zids = list(itertools.combinations(range(len(zlist)), 2))
+ print("Node combinations: \n", zids)
+
+ for i in range(xlist.shape[1]):
+ print("Node {} observed landmark with ID {}".format(i, zlist[i][0, 3]))
+
+
+.. parsed-literal::
+
+ Node combinations:
+ [(0, 1)]
+ Node 0 observed landmark with ID 0.0
+ Node 1 observed landmark with ID 0.0
+
+
+In the following code snippet the error based on the virtual measurement
+between node 0 and 1 will be created. The equations for the error is as follows:
+:math:`e_{ij}^x = x_j + d_j cos(\psi_j +\theta_j) - x_i - d_i cos(\psi_i + \theta_i)`
+
+:math:`e_{ij}^y = y_j + d_j sin(\psi_j + \theta_j) - y_i - d_i sin(\psi_i + \theta_i)`
+
+:math:`e_{ij}^x = \psi_j + \theta_j - \psi_i - \theta_i`
+
+Where :math:`[x_i, y_i, \psi_i]` is the pose for node :math:`i` and
+similarly for node :math:`j`, :math:`d` is the measured distance at
+nodes :math:`i` and :math:`j`, and :math:`\theta` is the measured
+bearing to the landmark. The difference is visualized with the figure in
+the next cell.
+
+In case of perfect motion and perfect measurement the error shall be
+zero since :math:`x_j + d_j cos(\psi_j + \theta_j)` should equal
+:math:`x_i + d_i cos(\psi_i + \theta_i)`
+
+.. code:: ipython3
+
+ # Initialize edges list
+ edges = []
+
+ # Go through all the different combinations
+ for (t1, t2) in zids:
+ x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1]
+ x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2]
+
+ # All nodes have valid observation with ID=0, therefore, no data association condition
+ iz1 = 0
+ iz2 = 0
+
+ d1 = zlist[t1][iz1, 0]
+ angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2]
+ d2 = zlist[t2][iz2, 0]
+ angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2]
+
+ # find angle between observation and horizontal
+ tangle1 = pi_2_pi(yaw1 + angle1)
+ tangle2 = pi_2_pi(yaw2 + angle2)
+
+ # project the observations
+ tmp1 = d1 * math.cos(tangle1)
+ tmp2 = d2 * math.cos(tangle2)
+ tmp3 = d1 * math.sin(tangle1)
+ tmp4 = d2 * math.sin(tangle2)
+
+ edge = Edge()
+ print(y1,y2, tmp3, tmp4)
+ # calculate the error of the virtual measurement
+ # node 1 as seen from node 2 throught the observations 1,2
+ edge.e[0, 0] = x2 - x1 - tmp1 + tmp2
+ edge.e[1, 0] = y2 - y1 - tmp3 + tmp4
+ edge.e[2, 0] = pi_2_pi(yaw2 - yaw1 - tangle1 + tangle2)
+
+ edge.d1, edge.d2 = d1, d2
+ edge.yaw1, edge.yaw2 = yaw1, yaw2
+ edge.angle1, edge.angle2 = angle1, angle2
+ edge.id1, edge.id2 = t1, t2
+
+ edges.append(edge)
+
+ print("For nodes",(t1,t2))
+ print("Added edge with errors: \n", edge.e)
+
+ # Visualize measurement projections
+ plt.plot(RFID[0, 0], RFID[0, 1], "*k", markersize=20)
+ plt.plot([x1,x2],[y1,y2], '.', markersize=50, alpha=0.8)
+ plt.plot([x1, x1 + graphics_radius * np.cos(yaw1)],
+ [y1, y1 + graphics_radius * np.sin(yaw1)], 'r')
+ plt.plot([x2, x2 + graphics_radius * np.cos(yaw2)],
+ [y2, y2 + graphics_radius * np.sin(yaw2)], 'r')
+
+ plt.plot([x1,x1+tmp1], [y1,y1], label="obs 1 x")
+ plt.plot([x2,x2+tmp2], [y2,y2], label="obs 2 x")
+ plt.plot([x1,x1], [y1,y1+tmp3], label="obs 1 y")
+ plt.plot([x2,x2], [y2,y2+tmp4], label="obs 2 y")
+ plt.plot(x1+tmp1, y1+tmp3, 'o')
+ plt.plot(x2+tmp2, y2+tmp4, 'o')
+ plt.legend()
+ plt.grid()
+ plt.show()
+
+
+.. parsed-literal::
+
+ 0.0 1.427649841628278 -2.0126109674819155 -3.524048014922737
+ For nodes (0, 1)
+ Added edge with errors:
+ [[-0.02 ]
+ [-0.084]
+ [ 0. ]]
+
+
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_9_1.png
+
+
+Since the constraints equations derived before are non-linear,
+linearization is needed before we can insert them into the information
+matrix and information vector. Two jacobians
+
+:math:`A = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_i}` as
+:math:`\boldsymbol{x}_i` holds the three variabls x, y, and theta.
+Similarly, :math:`B = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_j}`
+
+.. code:: ipython3
+
+ # Initialize the system information matrix and information vector
+ H = np.zeros((n, n))
+ b = np.zeros((n, 1))
+ x_opt = copy.deepcopy(hxDR)
+
+ for edge in edges:
+ id1 = edge.id1 * STATE_SIZE
+ id2 = edge.id2 * STATE_SIZE
+
+ t1 = edge.yaw1 + edge.angle1
+ A = np.array([[-1.0, 0, edge.d1 * math.sin(t1)],
+ [0, -1.0, -edge.d1 * math.cos(t1)],
+ [0, 0, -1.0]])
+
+ t2 = edge.yaw2 + edge.angle2
+ B = np.array([[1.0, 0, -edge.d2 * math.sin(t2)],
+ [0, 1.0, edge.d2 * math.cos(t2)],
+ [0, 0, 1.0]])
+
+ # TODO: use Qsim instead of sigma
+ sigma = np.diag([C_SIGMA1, C_SIGMA2, C_SIGMA3])
+ Rt1 = calc_rotational_matrix(tangle1)
+ Rt2 = calc_rotational_matrix(tangle2)
+ edge.omega = np.linalg.inv(Rt1 @ sigma @ Rt1.T + Rt2 @ sigma @ Rt2.T)
+
+ # Fill in entries in H and b
+ H[id1:id1 + STATE_SIZE, id1:id1 + STATE_SIZE] += A.T @ edge.omega @ A
+ H[id1:id1 + STATE_SIZE, id2:id2 + STATE_SIZE] += A.T @ edge.omega @ B
+ H[id2:id2 + STATE_SIZE, id1:id1 + STATE_SIZE] += B.T @ edge.omega @ A
+ H[id2:id2 + STATE_SIZE, id2:id2 + STATE_SIZE] += B.T @ edge.omega @ B
+
+ b[id1:id1 + STATE_SIZE] += (A.T @ edge.omega @ edge.e)
+ b[id2:id2 + STATE_SIZE] += (B.T @ edge.omega @ edge.e)
+
+
+ print("The determinant of H: ", np.linalg.det(H))
+ plt.figure()
+ plt.subplot(1,2,1)
+ plt.imshow(H, extent=[0, n, 0, n])
+ plt.subplot(1,2,2)
+ plt.imshow(b, extent=[0, 1, 0, n])
+ plt.show()
+
+ # Fix the origin, multiply by large number gives same results but better visualization
+ H[0:STATE_SIZE, 0:STATE_SIZE] += np.identity(STATE_SIZE)
+ print("The determinant of H after origin constraint: ", np.linalg.det(H))
+ plt.figure()
+ plt.subplot(1,2,1)
+ plt.imshow(H, extent=[0, n, 0, n])
+ plt.subplot(1,2,2)
+ plt.imshow(b, extent=[0, 1, 0, n])
+ plt.show()
+
+
+.. parsed-literal::
+
+ The determinant of H: 0.0
+ The determinant of H after origin constraint: 716.1972439134893
+
+
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_11_1.png
+
+.. image:: graphSLAM_doc_files/graphSLAM_doc_11_2.png
+
+.. code:: ipython3
+
+ # Find the solution (first iteration)
+ dx = - np.linalg.inv(H) @ b
+ for i in range(number_of_nodes):
+ x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0]
+ print("dx: \n",dx)
+ print("ground truth: \n ",hxTrue)
+ print("Odom: \n", hxDR)
+ print("SLAM: \n", x_opt)
+
+ # performance will improve with more iterations, nodes and landmarks.
+ print("\ngraphSLAM localization error: ", np.sum((x_opt - hxTrue) ** 2))
+ print("Odom localization error: ", np.sum((hxDR - hxTrue) ** 2))
+
+
+.. parsed-literal::
+
+ dx:
+ [[-0. ]
+ [-0. ]
+ [ 0. ]
+ [ 0.02 ]
+ [ 0.084]
+ [-0. ]]
+ ground truth:
+ [[0. 1.414]
+ [0. 1.414]
+ [0.785 0.985]]
+ Odom:
+ [[0. 1.428]
+ [0. 1.428]
+ [0.785 0.976]]
+ SLAM:
+ [[-0. 1.448]
+ [-0. 1.512]
+ [ 0.785 0.976]]
+
+ graphSLAM localization error: 0.010729072751057656
+ Odom localization error: 0.0004460978857535104
+
+
+The references:
+^^^^^^^^^^^^^^^
+
+- `The GraphSLAM Algorithm with Applications to Large-Scale Mapping of Urban Structures `_
+
+- `Introduction to Mobile Robotics Graph-Based SLAM `_
+
+- `A Tutorial on Graph-Based SLAM `_
+
+N.B. An additional step is required that uses the estimated path to
+update the belief regarding the map.
+
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png
new file mode 100644
index 0000000000..a985933346
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png
new file mode 100644
index 0000000000..a985933346
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png
new file mode 100644
index 0000000000..a8f70c4ff9
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png
new file mode 100644
index 0000000000..2074d3de17
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png
new file mode 100644
index 0000000000..4b8cfb25d1
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png
new file mode 100644
index 0000000000..1303dd5c99
Binary files /dev/null and b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png differ
diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_formulation.rst b/docs/modules/4_slam/graph_slam/graphSLAM_formulation.rst
new file mode 100644
index 0000000000..4978596c10
--- /dev/null
+++ b/docs/modules/4_slam/graph_slam/graphSLAM_formulation.rst
@@ -0,0 +1,218 @@
+.. _Graph SLAM Formulation:
+
+Graph SLAM Formulation
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+Author Jeff Irion
+
+Problem Formulation
+^^^^^^^^^^^^^^^^^^^
+
+Let a robot’s trajectory through its environment be represented by a
+sequence of :math:`N` poses:
+:math:`\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N`. Each pose lies
+on a manifold: :math:`\mathbf{p}_i \in \mathcal{M}`. Simple examples of
+manifolds used in Graph SLAM include 1-D, 2-D, and 3-D space, i.e.,
+:math:`\mathbb{R}`, :math:`\mathbb{R}^2`, and :math:`\mathbb{R}^3`.
+These environments are *rectilinear*, meaning that there is no concept
+of orientation. By contrast, in :math:`SE(2)` problem settings a robot’s
+pose consists of its location in :math:`\mathbb{R}^2` and its
+orientation :math:`\theta`. Similarly, in :math:`SE(3)` a robot’s pose
+consists of its location in :math:`\mathbb{R}^3` and its orientation,
+which can be represented via Euler angles, quaternions, or :math:`SO(3)`
+rotation matrices.
+
+As the robot explores its environment, it collects a set of :math:`M`
+measurements :math:`\mathcal{Z} = \{\mathbf{z}_j\}`. Examples of such
+measurements include odometry, GPS, and IMU data. Given a set of poses
+:math:`\mathbf{p}_1, \ldots, \mathbf{p}_N`, we can compute the estimated
+measurement
+:math:`\hat{\mathbf{z}}_j(\mathbf{p}_1, \ldots, \mathbf{p}_N)`. We can
+then compute the *residual*
+:math:`\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)` for measurement
+:math:`j`. The formula for the residual depends on the type of
+measurement. As an example, let :math:`\mathbf{z}_1` be an odometry
+measurement that was collected when the robot traveled from
+:math:`\mathbf{p}_1` to :math:`\mathbf{p}_2`. The expected measurement
+and the residual are computed as
+
+.. math::
+
+ \begin{aligned}
+ \hat{\mathbf{z}}_1(\mathbf{p}_1, \mathbf{p}_2) &= \mathbf{p}_2 \ominus \mathbf{p}_1 \\
+ \mathbf{e}_1(\mathbf{z}_1, \hat{\mathbf{z}}_1) &= \mathbf{z}_1 \ominus \hat{\mathbf{z}}_1 = \mathbf{z}_1 \ominus (\mathbf{p}_2 \ominus \mathbf{p}_1),\end{aligned}
+
+where the :math:`\ominus` operator indicates inverse pose composition.
+We model measurement :math:`\mathbf{z}_j` as having independent Gaussian
+noise with zero mean and covariance matrix :math:`\Omega_j^{-1}`; we
+refer to :math:`\Omega_j` as the *information matrix* for measurement
+:math:`j`. That is,
+
+.. math::
+ p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) = \eta_j \exp (-\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\mathsf{T}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)
+ :label: infomat
+
+where :math:`\eta_j` is the normalization constant.
+
+The objective of Graph SLAM is to find the maximum likelihood set of
+poses given the measurements :math:`\mathcal{Z} = \{\mathbf{z}_j\}`; in
+other words, we want to find
+
+.. math:: \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z})
+
+Using Bayes’ rule, we can write this probability as
+
+.. math::
+ \begin{aligned}
+ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \frac{p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) p(\mathbf{p}_1, \ldots, \mathbf{p}_N) }{ p(\mathcal{Z}) } \notag \\
+ &\propto p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N)
+ \end{aligned}
+ :label: bayes
+
+since :math:`p(\mathcal{Z})` is a constant (albeit, an unknown constant)
+and we assume that :math:`p(\mathbf{p}_1, \ldots, \mathbf{p}_N)` is
+uniformly distributed. Therefore, we
+can use Eq. :eq:`infomat` and and Eq. :eq:`bayes` to simplify the Graph SLAM
+optimization as follows:
+
+.. math::
+
+ \begin{aligned}
+ \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\
+ &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\
+ &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M \exp \left( -(\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right) \\
+ &= \mathop{\mathrm{arg\,min}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j).\end{aligned}
+
+We define
+
+.. math:: \chi^2 := \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j),
+
+and this is what we seek to minimize.
+
+Dimensionality and Pose Representation
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Before proceeding further, it is helpful to discuss the dimensionality
+of the problem. We have:
+
+- A set of :math:`N` poses
+ :math:`\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N`, where each
+ pose lies on the manifold :math:`\mathcal{M}`
+
+ - Each pose :math:`\mathbf{p}_i` is represented as a vector in (a
+ subset of) :math:`\mathbb{R}^d`. For example:
+
+ - An :math:`SE(2)` pose is typically represented as
+ :math:`(x, y, \theta)`, and thus :math:`d = 3`.
+
+ - An :math:`SE(3)` pose is typically represented as
+ :math:`(x, y, z, q_x, q_y, q_z, q_w)`, where :math:`(x, y, z)`
+ is a point in :math:`\mathbb{R}^3` and
+ :math:`(q_x, q_y, q_z, q_w)` is a *quaternion*, and so
+ :math:`d = 7`. For more information about :math:`SE(3)`
+ parameterization and pose transformations, see
+ [blanco2010tutorial]_.
+
+ - We also need to be able to represent each pose compactly as a
+ vector in (a subset of) :math:`\mathbb{R}^c`.
+
+ - Since an :math:`SE(2)` pose has three degrees of freedom, the
+ :math:`(x, y, \theta)` representation is again sufficient and
+ :math:`c=3`.
+
+ - An :math:`SE(3)` pose only has six degrees of freedom, and we
+ can represent it compactly as :math:`(x, y, z, q_x, q_y, q_z)`,
+ and thus :math:`c=6`.
+
+ - We use the :math:`\boxplus` operator to indicate pose composition
+ when one or both of the poses are represented compactly. The
+ output can be a pose in :math:`\mathcal{M}` or a vector in
+ :math:`\mathbb{R}^c`, as required by context.
+
+- A set of :math:`M` measurements
+ :math:`\mathcal{Z} = \{\mathbf{z}_1, \mathbf{z}_2, \ldots, \mathbf{z}_M\}`
+
+ - Each measurement’s dimensionality can be unique, and we will use
+ :math:`\bullet` to denote a “wildcard” variable.
+
+ - Measurement :math:`\mathbf{z}_j \in \mathbb{R}^\bullet` has an
+ associated information matrix
+ :math:`\Omega_j \in \mathbb{R}^{\bullet \times \bullet}` and
+ residual function
+ :math:`\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) = \mathbf{e}_j(\mathbf{z}_j, \mathbf{p}_1, \ldots, \mathbf{p}_N) \in \mathbb{R}^\bullet`.
+
+ - A measurement could, in theory, constrain anywhere from 1 pose to
+ all :math:`N` poses. In practice, each measurement usually
+ constrains only 1 or 2 poses.
+
+Graph SLAM Algorithm
+^^^^^^^^^^^^^^^^^^^^
+
+The “Graph” in Graph SLAM refers to the fact that we view the problem as
+a graph. The graph has a set :math:`\mathcal{V}` of :math:`N` vertices,
+where each vertex :math:`v_i` has an associated pose
+:math:`\mathbf{p}_i`. Similarly, the graph has a set :math:`\mathcal{E}`
+of :math:`M` edges, where each edge :math:`e_j` has an associated
+measurement :math:`\mathbf{z}_j`. In practice, the edges in this graph
+are either unary (i.e., a loop) or binary. (Note: :math:`e_j` refers to
+the edge in the graph associated with measurement :math:`\mathbf{z}_j`,
+whereas :math:`\mathbf{e}_j` refers to the residual function associated
+with :math:`\mathbf{z}_j`.) For more information about the Graph SLAM
+algorithm, see [grisetti2010tutorial]_.
+
+We want to optimize
+
+.. math:: \chi^2 = \sum_{e_j \in \mathcal{E}} \mathbf{e}_j^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j.
+
+Let :math:`\mathbf{x}_i \in \mathbb{R}^c` be the compact representation
+of pose :math:`\mathbf{p}_i \in \mathcal{M}`, and let
+
+.. math:: \mathbf{x} := \begin{bmatrix} \mathbf{x}_1 \\ \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \end{bmatrix} \in \mathbb{R}^{cN}
+
+We will solve this optimization problem iteratively. Let
+
+.. math:: \mathbf{x}^{k+1} := \mathbf{x}^k \boxplus \Delta \mathbf{x}^k = \begin{bmatrix} \mathbf{x}_1 \boxplus \Delta \mathbf{x}_1 \\ \mathbf{x}_2 \boxplus \Delta \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \boxplus \Delta \mathbf{x}_2 \end{bmatrix}
+ :label: update
+
+The :math:`\chi^2` error at iteration :math:`k+1` is
+
+.. math:: \chi_{k+1}^2 = \sum_{e_j \in \mathcal{E}} \underbrace{\left[ \mathbf{e}_j(\mathbf{x}^{k+1}) \right]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^{k+1})}_{\bullet \times 1}.
+ :label: chisq_at_kplusone
+
+We will linearize the residuals as:
+
+.. math::
+ \begin{aligned}
+ \mathbf{e}_j(\mathbf{x}^{k+1}) &= \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \\
+ &\approx \mathbf{e}_j(\mathbf{x}^{k}) + \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right] \Delta \mathbf{x}^k \\
+ &= \mathbf{e}_j(\mathbf{x}^{k}) + \left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right) \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \Delta \mathbf{x}^k.
+ \end{aligned}
+ :label: linearization
+
+Plugging :eq:`linearization` into :eq:`chisq_at_kplusone`, we get:
+
+.. math::
+
+ \begin{aligned}
+ \chi_{k+1}^2 &\approx \ \ \ \ \ \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x}^k)]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^k)}_{\bullet \times 1} \notag \\
+ &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\
+ &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{(\Delta \mathbf{x}^k)^{\scriptstyle{\mathsf{T}}}}_{1 \times cN} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^{\scriptstyle{\mathsf{T}}}}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^{\scriptstyle{\mathsf{T}}}}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\
+ &= \chi_k^2 + 2 \mathbf{b}^{\scriptstyle{\mathsf{T}}}\Delta \mathbf{x}^k + (\Delta \mathbf{x}^k)^{\scriptstyle{\mathsf{T}}}H \Delta \mathbf{x}^k, \notag\end{aligned}
+
+where
+
+.. math::
+
+ \begin{aligned}
+ \mathbf{b}^{\scriptstyle{\mathsf{T}}}&= \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \\
+ H &= \sum_{e_j \in \mathcal{E}} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^{\scriptstyle{\mathsf{T}}}}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^{\scriptstyle{\mathsf{T}}}}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN}.\end{aligned}
+
+Using this notation, we obtain the optimal update as
+
+.. math:: \Delta \mathbf{x}^k = -H^{-1} \mathbf{b}. \label{eq:deltax}
+
+We apply this update to the poses via :eq:`update` and repeat until convergence.
+
+
+.. [blanco2010tutorial] Blanco, J.-L.A tutorial onSE(3) transformation parameterization and on-manifold optimization.University of Malaga, Tech. Rep 3(2010)
+.. [grisetti2010tutorial] Grisetti, G., Kummerle, R., Stachniss, C., and Burgard, W.A tutorial on graph-based SLAM.IEEE Intelligent Transportation Systems Magazine 2, 4 (2010), 31–43.
+
diff --git a/docs/modules/4_slam/graph_slam/graph_slam_main.rst b/docs/modules/4_slam/graph_slam/graph_slam_main.rst
new file mode 100644
index 0000000000..2ef17e4179
--- /dev/null
+++ b/docs/modules/4_slam/graph_slam/graph_slam_main.rst
@@ -0,0 +1,30 @@
+Graph based SLAM
+----------------
+
+This is a graph based SLAM example.
+
+The blue line is ground truth.
+
+The black line is dead reckoning.
+
+The red line is the estimated trajectory with Graph based SLAM.
+
+The black stars are landmarks for graph edge generation.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif
+
+Code Link
+~~~~~~~~~~~~
+
+.. autofunction:: SLAM.GraphBasedSLAM.graph_based_slam.graph_based_slam
+
+
+.. include:: graphSLAM_doc.rst
+.. include:: graphSLAM_formulation.rst
+.. include:: graphSLAM_SE2_example.rst
+
+Reference
+~~~~~~~~~~~
+
+- `A Tutorial on Graph-Based SLAM `_
+
diff --git a/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst b/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst
new file mode 100644
index 0000000000..772fe62889
--- /dev/null
+++ b/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst
@@ -0,0 +1,22 @@
+.. _iterative-closest-point-(icp)-matching:
+
+Iterative Closest Point (ICP) Matching
+--------------------------------------
+
+This is a 2D ICP matching example with singular value decomposition.
+
+It can calculate a rotation matrix and a translation vector between
+points to points.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif
+
+Code Link
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+.. autofunction:: SLAM.ICPMatching.icp_matching.icp_matching
+
+
+References
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+- `Introduction to Mobile Robotics: Iterative Closest Point Algorithm `_
diff --git a/docs/modules/4_slam/slam_main.rst b/docs/modules/4_slam/slam_main.rst
new file mode 100644
index 0000000000..98211986c2
--- /dev/null
+++ b/docs/modules/4_slam/slam_main.rst
@@ -0,0 +1,18 @@
+.. _`SLAM`:
+
+SLAM
+====
+
+Simultaneous Localization and Mapping(SLAM) examples
+Simultaneous Localization and Mapping (SLAM) is an ability to estimate the pose of a robot and the map of the environment at the same time. The SLAM problem is hard to
+solve, because a map is needed for localization and localization is needed for mapping. In this way, SLAM is often said to be similar to a ‘chicken-and-egg’ problem. Popular SLAM solution methods include the extended Kalman filter, particle filter, and Fast SLAM algorithm[31]. Fig.4 shows SLAM simulation results using extended Kalman filter and results using FastSLAM2.0[31].
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ iterative_closest_point_matching/iterative_closest_point_matching
+ ekf_slam/ekf_slam
+ FastSLAM1/FastSLAM1
+ FastSLAM2/FastSLAM2
+ graph_slam/graph_slam
diff --git a/PathPlanning/BezierPath/Figure_1.png b/docs/modules/5_path_planning/bezier_path/Figure_1.png
similarity index 100%
rename from PathPlanning/BezierPath/Figure_1.png
rename to docs/modules/5_path_planning/bezier_path/Figure_1.png
diff --git a/PathPlanning/BezierPath/Figure_2.png b/docs/modules/5_path_planning/bezier_path/Figure_2.png
similarity index 100%
rename from PathPlanning/BezierPath/Figure_2.png
rename to docs/modules/5_path_planning/bezier_path/Figure_2.png
diff --git a/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst
new file mode 100644
index 0000000000..19fb89a1b1
--- /dev/null
+++ b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst
@@ -0,0 +1,27 @@
+Bezier path planning
+--------------------
+
+A sample code of Bezier path planning.
+
+It is based on 4 control points Beizer path.
+
+.. image:: Figure_1.png
+
+If you change the offset distance from start and end point,
+
+You can get different Beizer course:
+
+.. image:: Figure_2.png
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.BezierPath.bezier_path.calc_4points_bezier_path
+
+
+Reference
+~~~~~~~~~~~~~~~
+
+- `Continuous Curvature Path Generation Based on Bezier Curves for
+ Autonomous
+ Vehicles `__
diff --git a/docs/modules/5_path_planning/bspline_path/approx_and_curvature.png b/docs/modules/5_path_planning/bspline_path/approx_and_curvature.png
new file mode 100644
index 0000000000..49f260bb60
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/approx_and_curvature.png differ
diff --git a/docs/modules/5_path_planning/bspline_path/approximation1.png b/docs/modules/5_path_planning/bspline_path/approximation1.png
new file mode 100644
index 0000000000..d5f00551eb
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/approximation1.png differ
diff --git a/docs/modules/5_path_planning/bspline_path/basis_functions.png b/docs/modules/5_path_planning/bspline_path/basis_functions.png
new file mode 100644
index 0000000000..65075c8015
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/basis_functions.png differ
diff --git a/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst b/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst
new file mode 100644
index 0000000000..00e5ef2fdb
--- /dev/null
+++ b/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst
@@ -0,0 +1,146 @@
+B-Spline planning
+-----------------
+
+.. image:: bspline_path_planning.png
+
+This is a B-Spline path planning routines.
+
+If you input waypoints, it generates a smooth path with B-Spline curve.
+
+This codes provide two types of B-Spline curve generations:
+
+1. Interpolation: generate a curve that passes through all waypoints.
+
+2. Approximation: generate a curve that approximates the waypoints. (Not passing through all waypoints)
+
+Bspline basics
+~~~~~~~~~~~~~~
+
+BSpline (Basis-Spline) is a piecewise polynomial spline curve.
+
+It is expressed by the following equation.
+
+:math:`\mathbf{S}(x)=\sum_{i=k-p}^k \mathbf{c}_i B_{i, p}(x)`
+
+here:
+
+* :math:`S(x)` is the curve point on the spline at x.
+* :math:`c_i` is the representative point generating the spline, called the control point.
+* :math:`p+1` is the dimension of the BSpline.
+* :math:`k` is the number of knots.
+* :math:`B_{i,p}(x)` is a function called Basis Function.
+
+The the basis function can be calculated by the following `De Boor recursion formula `_:
+
+:math:`B_{i, 0}(x):= \begin{cases}1 & \text { if } \quad t_i \leq x`_.
+
+.. code-block:: python
+
+ from scipy.interpolate import BSpline
+
+ def B_orig(x, k, i, t):
+ if k == 0:
+ return 1.0 if t[i] <= x < t[i + 1] else 0.0
+ if t[i + k] == t[i]:
+ c1 = 0.0
+ else:
+ c1 = (x - t[i]) / (t[i + k] - t[i]) * B(x, k - 1, i, t)
+
+ if t[i + k + 1] == t[i + 1]:
+ c2 = 0.0
+ else:
+ c2 = (t[i + k + 1] - x) / (t[i + k + 1] - t[i + 1]) * B(x, k - 1, i + 1, t)
+ return c1 + c2
+
+
+ def B(x, k, i, t):
+ c = np.zeros_like(t)
+ c[i] = 1
+ return BSpline(t, c, k)(x)
+
+
+ def main():
+ k = 3 # degree of the spline
+ t = [0, 1, 2, 3, 4, 5] # knots vector
+
+ x = np.linspace(0, 5, 1000, endpoint=False)
+ t = np.r_[[np.min(t)]*k, t, [np.max(t)]*k]
+
+ n = len(t) - k - 1
+ for i in range(n):
+ y = np.array([B(ix, k, i, t) for ix in x])
+ plt.plot(x, y, label=f'i = {i}')
+
+ plt.title(f'Basis functions (k = {k}, knots = {t})')
+ plt.show()
+
+Bspline interpolation planning
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+:meth:`PathPlanning.BSplinePath.bspline_path.interpolate_b_spline_path` generates a curve that passes through all waypoints.
+
+This is a simple example of the interpolation planning:
+
+.. image:: interpolation1.png
+
+This figure also shows curvatures of each path point using :ref:`utils.plot.plot_curvature `.
+
+The default spline degree is 3, so curvature changes smoothly.
+
+.. image:: interp_and_curvature.png
+
+Code link
+++++++++++
+
+.. autofunction:: PathPlanning.BSplinePath.bspline_path.interpolate_b_spline_path
+
+
+Bspline approximation planning
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+:meth:`PathPlanning.BSplinePath.bspline_path.approximate_b_spline_path`
+generates a curve that approximates the waypoints, which means that
+the curve might not pass through waypoints.
+
+Users can adjust path smoothness by the smoothing parameter `s`. If this
+value is bigger, the path will be smoother, but it will be less accurate.
+If this value is smaller, the path will be more accurate, but it will be
+less smooth.
+
+This is a simple example of the approximation planning:
+
+.. image:: approximation1.png
+
+This figure also shows curvatures of each path point using :ref:`utils.plot.plot_curvature `.
+
+The default spline degree is 3, so curvature changes smoothly.
+
+.. image:: approx_and_curvature.png
+
+Code Link
+++++++++++
+
+.. autofunction:: PathPlanning.BSplinePath.bspline_path.approximate_b_spline_path
+
+
+References
+~~~~~~~~~~
+
+- `B-spline - Wikipedia `__
+- `scipy.interpolate.UnivariateSpline `__
\ No newline at end of file
diff --git a/docs/modules/5_path_planning/bspline_path/bspline_path_planning.png b/docs/modules/5_path_planning/bspline_path/bspline_path_planning.png
new file mode 100644
index 0000000000..a3c1e621f9
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/bspline_path_planning.png differ
diff --git a/docs/modules/5_path_planning/bspline_path/interp_and_curvature.png b/docs/modules/5_path_planning/bspline_path/interp_and_curvature.png
new file mode 100644
index 0000000000..54e291741c
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/interp_and_curvature.png differ
diff --git a/docs/modules/5_path_planning/bspline_path/interpolation1.png b/docs/modules/5_path_planning/bspline_path/interpolation1.png
new file mode 100644
index 0000000000..fb280343c9
Binary files /dev/null and b/docs/modules/5_path_planning/bspline_path/interpolation1.png differ
diff --git a/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst b/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst
new file mode 100644
index 0000000000..e1cd2fe353
--- /dev/null
+++ b/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst
@@ -0,0 +1,16 @@
+Bug planner
+-----------
+
+This is a 2D planning with Bug algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BugPlanner/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.BugPlanning.bug.main
+
+Reference
+~~~~~~~~~~~~
+
+- `ECE452 Bug Algorithms `_
diff --git a/docs/modules/5_path_planning/catmull_rom_spline/blending_functions.png b/docs/modules/5_path_planning/catmull_rom_spline/blending_functions.png
new file mode 100644
index 0000000000..928946df46
Binary files /dev/null and b/docs/modules/5_path_planning/catmull_rom_spline/blending_functions.png differ
diff --git a/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_path_planning.png b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_path_planning.png
new file mode 100644
index 0000000000..1d0ff001e6
Binary files /dev/null and b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_path_planning.png differ
diff --git a/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst
new file mode 100644
index 0000000000..fa2a2ff72b
--- /dev/null
+++ b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst
@@ -0,0 +1,103 @@
+Catmull-Rom Spline Planning
+----------------------------
+
+.. image:: catmull_rom_path_planning.png
+
+This is a Catmull-Rom spline path planning routine.
+
+If you provide waypoints, the Catmull-Rom spline generates a smooth path that always passes through the control points,
+exhibits local control, and maintains 𝐶1 continuity.
+
+
+Catmull-Rom Spline Fundamentals
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Catmull-Rom splines are a type of cubic spline that passes through a given set of points, known as control points.
+
+They are defined by the following equation for calculating a point on the spline:
+
+:math:`P(t) = 0.5 \times \left( 2P_1 + (-P_0 + P_2)t + (2P_0 - 5P_1 + 4P_2 - P_3)t^2 + (-P_0 + 3P_1 - 3P_2 + P_3)t^3 \right)`
+
+Where:
+
+* :math:`P(t)` is the point on the spline at parameter :math:`t`.
+* :math:`P_0, P_1, P_2, P_3` are the control points surrounding the parameter :math:`t`.
+
+Types of Catmull-Rom Splines
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+There are different types of Catmull-Rom splines based on the choice of the **tau** parameter, which influences how the curve
+behaves in relation to the control points:
+
+1. **Uniform Catmull-Rom Spline**:
+ The standard implementation where the parameterization is uniform. Each segment of the spline is treated equally,
+ regardless of the distances between control points.
+
+
+2. **Chordal Catmull-Rom Spline**:
+ This spline type takes into account the distance between control points. The parameterization is based on the actual distance
+ along the spline, ensuring smoother transitions. The equation can be modified to include the chord length :math:`L_i` between
+ points :math:`P_i` and :math:`P_{i+1}`:
+
+ .. math::
+ \tau_i = \sqrt{(x_{i+1} - x_i)^2 + (y_{i+1} - y_i)^2}
+
+3. **Centripetal Catmull-Rom Spline**:
+ This variation improves upon the chordal spline by using the square root of the distance to determine the parameterization,
+ which avoids oscillations and creates a more natural curve. The parameter :math:`t_i` is adjusted using the following relation:
+
+ .. math::
+ t_i = \sqrt{(x_{i+1} - x_i)^2 + (y_{i+1} - y_i)^2}
+
+
+Blending Functions
+~~~~~~~~~~~~~~~~~~~~~
+
+In Catmull-Rom spline interpolation, blending functions are used to calculate the influence of each control point on the spline at a
+given parameter :math:`t`. The blending functions ensure that the spline is smooth and passes through the control points while
+maintaining continuity. The four blending functions used in Catmull-Rom splines are defined as follows:
+
+1. **Blending Function 1**:
+
+ .. math::
+ b_1(t) = -t + 2t^2 - t^3
+
+2. **Blending Function 2**:
+
+ .. math::
+ b_2(t) = 2 - 5t^2 + 3t^3
+
+3. **Blending Function 3**:
+
+ .. math::
+ b_3(t) = t + 4t^2 - 3t^3
+
+4. **Blending Function 4**:
+
+ .. math::
+ b_4(t) = -t^2 + t^3
+
+The blending functions are combined in the spline equation to create a smooth curve that reflects the influence of each control point.
+
+The following figure illustrates the blending functions over the interval :math:`[0, 1]`:
+
+.. image:: blending_functions.png
+
+Catmull-Rom Spline API
+~~~~~~~~~~~~~~~~~~~~~~~
+
+This section provides an overview of the functions used for Catmull-Rom spline path planning.
+
+Code Link
+++++++++++
+
+.. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_point
+
+.. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_spline
+
+
+References
+~~~~~~~~~~~~~~
+
+- `Catmull-Rom Spline - Wikipedia `__
+- `Catmull-Rom Splines `__
\ No newline at end of file
diff --git a/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst b/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst
new file mode 100644
index 0000000000..16d0ec03c1
--- /dev/null
+++ b/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst
@@ -0,0 +1,85 @@
+.. _clothoid-path-planning:
+
+Clothoid path planning
+--------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation1.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation2.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation3.gif
+
+This is a clothoid path planning sample code.
+
+This can interpolate two 2D pose (x, y, yaw) with a clothoid path,
+which its curvature is linearly continuous.
+In other words, this is G1 Hermite interpolation with a single clothoid segment.
+
+This path planning algorithm as follows:
+
+Step1: Solve g function
+~~~~~~~~~~~~~~~~~~~~~~~
+
+Solve the g(A) function with a nonlinear optimization solver.
+
+.. math::
+
+ g(A):=Y(2A, \delta-A, \phi_{s})
+
+Where
+
+* :math:`\delta`: the orientation difference between start and goal pose.
+* :math:`\phi_{s}`: the orientation of the start pose.
+* :math:`Y`: :math:`Y(a, b, c)=\int_{0}^{1} \sin \left(\frac{a}{2} \tau^{2}+b \tau+c\right) d \tau`
+
+
+Step2: Calculate path parameters
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+We can calculate these path parameters using :math:`A`,
+
+:math:`L`: path length
+
+.. math::
+
+ L=\frac{R}{X\left(2 A, \delta-A, \phi_{s}\right)}
+
+where
+
+* :math:`R`: the distance between start and goal pose
+* :math:`X`: :math:`X(a, b, c)=\int_{0}^{1} \cos \left(\frac{a}{2} \tau^{2}+b \tau+c\right) d \tau`
+
+
+- :math:`\kappa`: curvature
+
+.. math::
+
+ \kappa=(\delta-A) / L
+
+
+- :math:`\kappa'`: curvature rate
+
+.. math::
+
+ \kappa^{\prime}=2 A / L^{2}
+
+
+Step3: Construct a path with Fresnel integral
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The final clothoid path can be calculated with the path parameters and Fresnel integrals.
+
+.. math::
+ \begin{aligned}
+ &x(s)=x_{0}+\int_{0}^{s} \cos \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau \\
+ &y(s)=y_{0}+\int_{0}^{s} \sin \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau
+ \end{aligned}
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.ClothoidPath.clothoid_path_planner.generate_clothoid_path
+
+
+References
+~~~~~~~~~~
+
+- `Fast and accurate G1 fitting of clothoid curves `__
diff --git a/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst b/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst
new file mode 100644
index 0000000000..eaa876c80b
--- /dev/null
+++ b/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst
@@ -0,0 +1,55 @@
+Coverage path planner
+---------------------
+
+Grid based sweep
+~~~~~~~~~~~~~~~~
+
+This is a 2D grid based sweep coverage path planner simulation:
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/GridBasedSweepCPP/animation.gif
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.GridBasedSweepCPP.grid_based_sweep_coverage_path_planner.planning
+
+Spiral Spanning Tree
+~~~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based spiral spanning tree coverage path planner simulation:
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation1.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation2.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation3.gif
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.SpiralSpanningTreeCPP.spiral_spanning_tree_coverage_path_planner.main
+
+Reference
++++++++++++++
+
+- `Spiral-STC: An On-Line Coverage Algorithm of Grid Environments by a Mobile Robot `_
+
+
+Wavefront path
+~~~~~~~~~~~~~~
+
+This is a 2D grid based wavefront coverage path planner simulation:
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation1.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation2.gif
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation3.gif
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.WavefrontCPP.wavefront_coverage_path_planner.wavefront
+
+Reference
++++++++++++++
+
+- `Planning paths of complete coverage of an unstructured environment by a mobile robot `_
+
+
diff --git a/docs/modules/5_path_planning/cubic_spline/cubic_spline_1d.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_1d.png
new file mode 100644
index 0000000000..f3572089b9
Binary files /dev/null and b/docs/modules/5_path_planning/cubic_spline/cubic_spline_1d.png differ
diff --git a/PathPlanning/CubicSpline/Figure_3.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_curvature.png
similarity index 100%
rename from PathPlanning/CubicSpline/Figure_3.png
rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_curvature.png
diff --git a/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_path.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_path.png
new file mode 100644
index 0000000000..e2cd467add
Binary files /dev/null and b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_path.png differ
diff --git a/PathPlanning/CubicSpline/Figure_2.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_yaw.png
similarity index 100%
rename from PathPlanning/CubicSpline/Figure_2.png
rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_yaw.png
diff --git a/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst b/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst
new file mode 100644
index 0000000000..a110217a2e
--- /dev/null
+++ b/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst
@@ -0,0 +1,213 @@
+Cubic spline planning
+---------------------
+
+Spline curve continuity
+~~~~~~~~~~~~~~~~~~~~~~~~
+
+Spline curve smoothness is depending on the which kind of spline model is used.
+
+The smoothness of the spline curve is expressed as :math:`C_0, C_1`, and so on.
+
+This representation represents continuity of the curve.
+For example, for a spline curve in two-dimensional space:
+
+- :math:`C_0` is position continuous
+- :math:`C_1` is tangent vector continuous
+- :math:`C_2` is curvature vector continuous
+
+as shown in the following figure:
+
+.. image:: spline_continuity.png
+
+Cubic spline can generate a curve with :math:`C_0, C_1, C_2`.
+
+1D cubic spline
+~~~~~~~~~~~~~~~~~~~
+
+Cubic spline interpolation is a method of smoothly
+interpolating between multiple data points when given
+multiple data points, as shown in the figure below.
+
+.. image:: spline.png
+
+It separates between each interval between data points.
+
+The each interval part is approximated by each cubic polynomial.
+
+The cubic spline uses the cubic polynomial equation for interpolation:
+
+:math:`S_j(x)=a_j+b_j(x-x_j)+c_j(x-x_j)^2+d_j(x-x_j)^3`
+
+where :math:`x_j < x < x_{j+1}`, :math:`x_j` is the j-th node of the spline,
+:math:`a_j`, :math:`b_j`, :math:`c_j`, :math:`d_j` are the coefficients
+of the spline.
+
+As the above equation, there are 4 unknown parameters :math:`(a,b,c,d)` for
+one interval, so if the number of data points is :math:`N`, the
+interpolation has :math:`4N` unknown parameters.
+
+The following five conditions are used to determine the :math:`4N`
+unknown parameters:
+
+Constraint 1: Terminal constraints
+===================================
+
+:math:`S_j(x_j)=y_j`
+
+This constraint is the terminal constraint of each interval.
+
+The polynomial of each interval will pass through the x,y coordinates of
+the data points.
+
+Constraint 2: Point continuous constraints
+============================================
+
+:math:`S_j(x_{j+1})=S_{j+1}(x_{j+1})=y_{j+1}`
+
+This constraint is a continuity condition for the boundary of each interval.
+
+This constraint ensures that the boundary of each interval is continuous.
+
+Constraint 3: Tangent vector continuous constraints
+====================================================
+
+:math:`S'_j(x_{j+1})=S'_{j+1}(x_{j+1})`
+
+This constraint is a continuity condition for the first derivative of
+the boundary of each interval.
+
+This constraint makes the vectors of the boundaries of each
+interval continuous.
+
+
+Constraint 4: Curvature continuous constraints
+==============================================
+
+:math:`S''_j(x_{j+1})=S''_{j+1}(x_{j+1})`
+
+This constraint is the continuity condition for the second derivative of
+the boundary of each interval.
+
+This constraint makes the curvature of the boundaries of each
+interval continuous.
+
+
+Constraint 5: Terminal curvature constraints
+========================================================
+
+:math:`S''_0(0)=S''_{n+1}(x_{n})=0`.
+
+The constraint is a boundary condition for the second derivative of the starting and ending points.
+
+Our sample code assumes these terminal curvatures are 0, which is well known as Natural Cubic Spline.
+
+How to calculate the unknown parameters :math:`a_j, b_j, c_j, d_j`
+===================================================================
+
+Step1: calculate :math:`a_j`
++++++++++++++++++++++++++++++
+
+Spline coefficients :math:`a_j` can be calculated by y positions of the data points:
+
+:math:`a_j = y_i`.
+
+Step2: calculate :math:`c_j`
++++++++++++++++++++++++++++++
+
+Spline coefficients :math:`c_j` can be calculated by solving the linear equation:
+
+:math:`Ac_j = B`.
+
+The matrix :math:`A` and :math:`B` are defined as follows:
+
+.. math::
+ A=\left[\begin{array}{cccccc}
+ 1 & 0 & 0 & 0 & \cdots & 0 \\
+ h_{0} & 2\left(h_{0}+h_{1}\right) & h_{1} & 0 & \cdots & 0 \\
+ 0 & h_{1} & 2\left(h_{1}+h_{2}\right) & h_{2} & \cdots & 0 \\
+ 0 & 0 & h_{2} & 2\left(h_{2}+h_{3}\right) & \cdots & 0 \\
+ 0 & 0 & 0 & h_{3} & \ddots & \\
+ \vdots & \vdots & & & & \\
+ 0 & 0 & 0 & \cdots & 0 & 1
+ \end{array}\right]
+
+.. math::
+ B=\left[\begin{array}{c}
+ 0 \\
+ \frac{3}{h_{1}}\left(a_{2}-a_{1}\right)-\frac{3}{h_{0}}\left(a_{1}-a_{0}\right) \\
+ \vdots \\
+ \frac{3}{h_{n-1}}\left(a_{n}-a_{n-1}\right)-\frac{3}{h_{n-2}}\left(a_{n-1}-a_{n-2}\right) \\
+ 0
+ \end{array}\right]
+
+where :math:`h_{i}` is the x position distance between the i-th and (i+1)-th data points.
+
+Step3: calculate :math:`d_j`
++++++++++++++++++++++++++++++
+
+Spline coefficients :math:`d_j` can be calculated by the following equation:
+
+:math:`d_{j}=\frac{c_{j+1}-c_{j}}{3 h_{j}}`
+
+Step4: calculate :math:`b_j`
++++++++++++++++++++++++++++++
+
+Spline coefficients :math:`b_j` can be calculated by the following equation:
+
+:math:`b_{i}=\frac{1}{h_i}(a_{i+1}-a_{i})-\frac{h_i}{3}(2c_{i}+c_{i+1})`
+
+How to calculate the first and second derivatives of the spline curve
+======================================================================
+
+After we can get the coefficients of the spline curve, we can calculate
+
+the first derivative by:
+
+:math:`y^{\prime}(x)=b+2cx+3dx^2`
+
+the second derivative by:
+
+:math:`y^{\prime \prime}(x)=2c+6dx`
+
+These equations can be calculated by differentiating the cubic polynomial.
+
+Code Link
+==========
+
+This is the 1D cubic spline class API:
+
+.. autoclass:: PathPlanning.CubicSpline.cubic_spline_planner.CubicSpline1D
+ :members:
+
+2D cubic spline
+~~~~~~~~~~~~~~~~~~~
+
+Data x positions needs to be mono-increasing for 1D cubic spline.
+
+So, it cannot be used for 2D path planning.
+
+2D cubic spline uses two 1D cubic splines based on path distance from
+the start point for each dimension x and y.
+
+This can generate a curvature continuous path based on x-y waypoints.
+
+Heading angle of each point can be calculated analytically by:
+
+:math:`\theta=\tan ^{-1} \frac{y’}{x’}`
+
+Curvature of each point can be also calculated analytically by:
+
+:math:`\kappa=\frac{y^{\prime \prime} x^{\prime}-x^{\prime \prime} y^{\prime}}{\left(x^{\prime2}+y^{\prime2}\right)^{\frac{2}{3}}}`
+
+Code Link
+==========
+
+.. autoclass:: PathPlanning.CubicSpline.cubic_spline_planner.CubicSpline2D
+ :members:
+
+References
+~~~~~~~~~~
+- `Cubic Splines James Keesling `__
+- `Curves and Splines `__
+
+
diff --git a/docs/modules/5_path_planning/cubic_spline/spline.png b/docs/modules/5_path_planning/cubic_spline/spline.png
new file mode 100644
index 0000000000..d6bcb30c6e
Binary files /dev/null and b/docs/modules/5_path_planning/cubic_spline/spline.png differ
diff --git a/docs/modules/5_path_planning/cubic_spline/spline_continuity.png b/docs/modules/5_path_planning/cubic_spline/spline_continuity.png
new file mode 100644
index 0000000000..0b1e1abd70
Binary files /dev/null and b/docs/modules/5_path_planning/cubic_spline/spline_continuity.png differ
diff --git a/docs/modules/5_path_planning/dubins_path/RLR.jpg b/docs/modules/5_path_planning/dubins_path/RLR.jpg
new file mode 100644
index 0000000000..ff961e5e2d
Binary files /dev/null and b/docs/modules/5_path_planning/dubins_path/RLR.jpg differ
diff --git a/docs/modules/5_path_planning/dubins_path/RSR.jpg b/docs/modules/5_path_planning/dubins_path/RSR.jpg
new file mode 100644
index 0000000000..0af2692790
Binary files /dev/null and b/docs/modules/5_path_planning/dubins_path/RSR.jpg differ
diff --git a/docs/modules/5_path_planning/dubins_path/dubins_path.jpg b/docs/modules/5_path_planning/dubins_path/dubins_path.jpg
new file mode 100644
index 0000000000..ed4c67f2dc
Binary files /dev/null and b/docs/modules/5_path_planning/dubins_path/dubins_path.jpg differ
diff --git a/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst b/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst
new file mode 100644
index 0000000000..5a3d14464b
--- /dev/null
+++ b/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst
@@ -0,0 +1,76 @@
+Dubins path planning
+--------------------
+
+A sample code for Dubins path planning.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True
+
+Dubins path
+~~~~~~~~~~~~
+Dubins path is a analytical path planning algorithm for a simple car model.
+
+It can generates a shortest path between two 2D poses (x, y, yaw) with maximum curvature constraint and tangent(yaw angle) constraint.
+
+Generated paths consist of 3 segments of maximum curvature curves or a straight line segment.
+
+Each segment type can is categorized by 3 type: 'Right turn (R)' , 'Left turn (L)', and 'Straight (S).'
+
+Possible path will be at least one of these six types: RSR, RSL, LSR, LSL, RLR, LRL.
+
+Dubins path planner can output each segment type and distance of each course segment.
+
+For example, a RSR Dubins path is:
+
+.. image:: RSR.jpg
+ :width: 400px
+
+Each segment distance can be calculated by:
+
+:math:`\alpha = mod(-\theta)`
+
+:math:`\beta = mod(x_{e, yaw} - \theta)`
+
+:math:`p^2 = 2 + d ^ 2 - 2\cos(\alpha-\beta) + 2d(\sin\alpha - \sin\beta)`
+
+:math:`t = atan2(\cos\beta - \cos\alpha, d + \sin\alpha - \sin\beta)`
+
+:math:`d_1 = mod(-\alpha + t)`
+
+:math:`d_2 = p`
+
+:math:`d_3 = mod(\beta - t)`
+
+where :math:`\theta` is tangent and d is distance from :math:`x_s` to :math:`x_e`
+
+A RLR Dubins path is:
+
+.. image:: RLR.jpg
+ :width: 200px
+
+Each segment distance can be calculated by:
+
+:math:`t = (6.0 - d^2 + 2\cos(\alpha-\beta) + 2d(\sin\alpha - \sin\beta)) / 8.0`
+
+:math:`d_2 = mod(2\pi - acos(t))`
+
+:math:`d_1 = mod(\alpha - atan2(\cos\beta - \cos\alpha, d + \sin\alpha - \sin\beta) + d_2 / 2.0)`
+
+:math:`d_3 = mod(\alpha - \beta - d_1 + d_2)`
+
+You can generate a path from these information and the maximum curvature information.
+
+A path type which has minimum course length among 6 types is selected,
+and then a path is constructed based on the selected type and its distances.
+
+Code Link
+~~~~~~~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.DubinsPath.dubins_path_planner.plan_dubins_path
+
+
+Reference
+~~~~~~~~~~~~~~~~~~~~
+- `On Curves of Minimal Length with a Constraint on Average Curvature, and with Prescribed Initial and Terminal Positions and Tangents `__
+- `Dubins path - Wikipedia `__
+- `15.3.1 Dubins Curves `__
+- `A Comprehensive, Step-by-Step Tutorial to Computing Dubin’s Paths `__
diff --git a/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst b/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst
new file mode 100644
index 0000000000..ac5322df94
--- /dev/null
+++ b/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst
@@ -0,0 +1,21 @@
+.. _dynamic_window_approach:
+
+Dynamic Window Approach
+-----------------------
+
+This is a 2D navigation sample code with Dynamic Window Approach.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.DynamicWindowApproach.dynamic_window_approach.dwa_control
+
+
+Reference
+~~~~~~~~~~~~
+
+- `The Dynamic Window Approach to Collision
+ Avoidance `__
+
diff --git a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst
new file mode 100644
index 0000000000..d0109d4ec3
--- /dev/null
+++ b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst
@@ -0,0 +1,79 @@
+Elastic Bands
+-------------
+
+This is a path planning with Elastic Bands.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ElasticBands/animation.gif
+
+Code Link
++++++++++++++
+
+.. autoclass:: PathPlanning.ElasticBands.elastic_bands.ElasticBands
+
+
+Core Concept
+~~~~~~~~~~~~
+- **Elastic Band**: A dynamically deformable collision-free path initialized by a global planner.
+- **Objective**:
+
+ * Shorten and smooth the path.
+ * Maximize obstacle clearance.
+ * Maintain global path connectivity.
+
+Bubble Representation
+~~~~~~~~~~~~~~~~~~~~~~~~
+- **Definition**: A local free-space region around configuration :math:`b`:
+
+ .. math::
+ B(b) = \{ q: \|q - b\| < \rho(b) \},
+
+ where :math:`\rho(b)` is the radius of the bubble.
+
+
+Force-Based Deformation
+~~~~~~~~~~~~~~~~~~~~~~~
+The elastic band deforms under artificial forces:
+
+Internal Contraction Force
+++++++++++++++++++++++++++
+- **Purpose**: Reduces path slack and length.
+- **Formula**: For node :math:`b_i`:
+
+ .. math::
+ f_c(b_i) = k_c \left( \frac{b_{i-1} - b_i}{\|b_{i-1} - b_i\|} + \frac{b_{i+1} - b_i}{\|b_{i+1} - b_i\|} \right)
+
+ where :math:`k_c` is the contraction gain.
+
+External Repulsion Force
++++++++++++++++++++++++++
+- **Purpose**: Pushes the path away from obstacles.
+- **Formula**: For node :math:`b_i`:
+
+ .. math::
+ f_r(b_i) = \begin{cases}
+ k_r (\rho_0 - \rho(b_i)) \nabla \rho(b_i) & \text{if } \rho(b_i) < \rho_0, \\
+ 0 & \text{otherwise}.
+ \end{cases}
+
+ where :math:`k_r` is the repulsion gain, :math:`\rho_0` is the maximum distance for applying repulsion force, and :math:`\nabla \rho(b_i)` is approximated via finite differences:
+
+ .. math::
+ \frac{\partial \rho}{\partial x} \approx \frac{\rho(b_i + h) - \rho(b_i - h)}{2h}.
+
+Dynamic Path Maintenance
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+1. **Node Update**:
+
+ .. math::
+ b_i^{\text{new}} = b_i^{\text{old}} + \alpha (f_c + f_r),
+
+ where :math:`\alpha` is a step-size parameter, which often proportional to :math:`\rho(b_i^{\text{old}})`
+
+2. **Overlap Enforcement**:
+- Insert new nodes if adjacent nodes are too far apart
+- Remove redundant nodes if adjacent nodes are too close
+
+References
++++++++++++++
+
+- `Elastic Bands: Connecting Path Planning and Control `__
diff --git a/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst
new file mode 100644
index 0000000000..9ee343e8a7
--- /dev/null
+++ b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst
@@ -0,0 +1,20 @@
+.. _eta^3-spline-path-planning:
+
+Eta^3 Spline path planning
+--------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif
+
+This is a path planning with Eta^3 spline.
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autoclass:: PathPlanning.Eta3SplineTrajectory.eta3_spline_trajectory.Eta3SplineTrajectory
+
+
+Reference
+~~~~~~~~~~~~~~~
+
+- `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile
+ Robots `__
diff --git a/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst
new file mode 100644
index 0000000000..0f84d381ea
--- /dev/null
+++ b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst
@@ -0,0 +1,52 @@
+Optimal Trajectory in a Frenet Frame
+------------------------------------
+
+This is optimal trajectory generation in a Frenet Frame.
+
+The cyan line is the target course and black crosses are obstacles.
+
+The red line is predicted path.
+
+Code Link
+~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.FrenetOptimalTrajectory.frenet_optimal_trajectory.main
+
+
+High Speed and Velocity Keeping Scenario
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_velocity_keeping_frenet_path.gif
+
+This scenario shows how the trajectory is maintained at high speeds while keeping a consistent velocity.
+
+High Speed and Merging and Stopping Scenario
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_merging_and_stopping_frenet_path.gif
+
+This scenario demonstrates the trajectory planning at high speeds with merging and stopping behaviors.
+
+Low Speed and Velocity Keeping Scenario
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/low_speed_and_velocity_keeping_frenet_path.gif
+
+This scenario demonstrates how the trajectory is managed at low speeds while maintaining a steady velocity.
+
+Low Speed and Merging and Stopping Scenario
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/low_speed_and_merging_and_stopping_frenet_path.gif
+
+This scenario illustrates the trajectory planning at low speeds with merging and stopping behaviors.
+
+Reference
+
+- `Optimal Trajectory Generation for Dynamic Street Scenarios in a
+ Frenet
+ Frame `__
+
+- `Optimal trajectory generation for dynamic street scenarios in a
+ Frenet Frame `__
+
diff --git a/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst
new file mode 100644
index 0000000000..c4aa6882aa
--- /dev/null
+++ b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst
@@ -0,0 +1,145 @@
+Grid based search
+-----------------
+
+Breadth First Search
+~~~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based path planning with Breadth first search algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BreadthFirstSearch/animation.gif
+
+In the animation, cyan points are searched nodes.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.BreadthFirstSearch.breadth_first_search.BreadthFirstSearchPlanner
+
+
+Depth First Search
+~~~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based path planning with Depth first search algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DepthFirstSearch/animation.gif
+
+In the animation, cyan points are searched nodes.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.DepthFirstSearch.depth_first_search.DepthFirstSearchPlanner
+
+
+.. _dijkstra:
+
+Dijkstra algorithm
+~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based shortest path planning with Dijkstra's algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif
+
+In the animation, cyan points are searched nodes.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.Dijkstra.dijkstra.DijkstraPlanner
+
+
+.. _a*-algorithm:
+
+A\* algorithm
+~~~~~~~~~~~~~
+
+This is a 2D grid based shortest path planning with A star algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif
+
+In the animation, cyan points are searched nodes.
+
+Its heuristic is 2D Euclid distance.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.AStar.a_star.AStarPlanner
+
+
+Bidirectional A\* algorithm
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based shortest path planning with bidirectional A star algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BidirectionalAStar/animation.gif
+
+In the animation, cyan points are searched nodes.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.BidirectionalAStar.bidirectional_a_star.BidirectionalAStarPlanner
+
+
+.. _D*-algorithm:
+
+D\* algorithm
+~~~~~~~~~~~~~
+
+This is a 2D grid based shortest path planning with D star algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStar/animation.gif
+
+The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm.
+
+Code Link
++++++++++++++
+
+.. autoclass:: PathPlanning.DStar.dstar.Dstar
+
+
+Reference
+++++++++++++
+
+- `D* search Wikipedia `__
+
+D\* lite algorithm
+~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based path planning and replanning with D star lite algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStarLite/animation.gif
+
+Code Link
++++++++++++++
+
+.. autoclass:: PathPlanning.DStarLite.d_star_lite.DStarLite
+
+Reference
+++++++++++++
+
+- `Improved Fast Replanning for Robot Navigation in Unknown Terrain `_
+
+
+Potential Field algorithm
+~~~~~~~~~~~~~~~~~~~~~~~~~
+
+This is a 2D grid based path planning with Potential Field algorithm.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif
+
+In the animation, the blue heat map shows potential value on each grid.
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.PotentialFieldPlanning.potential_field_planning.potential_field_planning
+
+
+Reference
+++++++++++++
+
+- `Robotic Motion Planning:Potential
+ Functions `__
+
diff --git a/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst b/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst
new file mode 100644
index 0000000000..36f340e0c2
--- /dev/null
+++ b/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst
@@ -0,0 +1,11 @@
+Hybrid a star
+---------------------
+
+This is a simple vehicle model based hybrid A\* path planner.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/HybridAStar/animation.gif
+
+Code Link
++++++++++++++
+
+.. autofunction:: PathPlanning.HybridAStar.hybrid_a_star.hybrid_a_star_planning
diff --git a/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst b/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst
new file mode 100644
index 0000000000..1eb1e4d840
--- /dev/null
+++ b/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst
@@ -0,0 +1,11 @@
+LQR based path planning
+-----------------------
+
+A sample code using LQR based path planning for double integrator model.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true
+
+Code Link
++++++++++++++
+
+.. autoclass:: PathPlanning.LQRPlanner.lqr_planner.LQRPlanner
diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png b/docs/modules/5_path_planning/model_predictive_trajectory_generator/lookup_table.png
similarity index 100%
rename from PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png
rename to docs/modules/5_path_planning/model_predictive_trajectory_generator/lookup_table.png
diff --git a/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst
new file mode 100644
index 0000000000..76472a6792
--- /dev/null
+++ b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst
@@ -0,0 +1,29 @@
+Model Predictive Trajectory Generator
+-------------------------------------
+
+This is a path optimization sample on model predictive trajectory
+generator.
+
+This algorithm is used for state lattice planner.
+
+Code Link
+~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.ModelPredictiveTrajectoryGenerator.trajectory_generator.optimize_trajectory
+
+
+Path optimization sample
+~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif
+
+Lookup table generation sample
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: lookup_table.png
+
+Reference
+~~~~~~~~~~~~
+
+- `Optimal rough terrain trajectory generation for wheeled mobile
+ robots `__
diff --git a/docs/modules/5_path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst
new file mode 100644
index 0000000000..0c84a19c22
--- /dev/null
+++ b/docs/modules/5_path_planning/path_planning_main.rst
@@ -0,0 +1,35 @@
+.. _`Path Planning`:
+
+Path Planning
+=============
+
+Path planning is the ability of a robot to search feasible and efficient path to the goal. The path has to satisfy some constraints based on the robot’s motion model and obstacle positions, and optimize some objective functions such as time to goal and distance to obstacle. In path planning, dynamic programming based approaches and sampling based approaches are widely used[22]. Fig.5 shows simulation results of potential field path planning and LQRRRT* path planning[27].
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ dynamic_window_approach/dynamic_window_approach
+ bugplanner/bugplanner
+ grid_base_search/grid_base_search
+ time_based_grid_search/time_based_grid_search
+ model_predictive_trajectory_generator/model_predictive_trajectory_generator
+ state_lattice_planner/state_lattice_planner
+ prm_planner/prm_planner
+ visibility_road_map_planner/visibility_road_map_planner
+ vrm_planner/vrm_planner
+ rrt/rrt
+ cubic_spline/cubic_spline
+ bspline_path/bspline_path
+ catmull_rom_spline/catmull_rom_spline
+ clothoid_path/clothoid_path
+ eta3_spline/eta3_spline
+ bezier_path/bezier_path
+ quintic_polynomials_planner/quintic_polynomials_planner
+ dubins_path/dubins_path
+ reeds_shepp_path/reeds_shepp_path
+ lqr_path/lqr_path
+ hybridastar/hybridastar
+ frenet_frame_path/frenet_frame_path
+ coverage_path/coverage_path
+ elastic_bands/elastic_bands
\ No newline at end of file
diff --git a/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst
new file mode 100644
index 0000000000..d58d1e2633
--- /dev/null
+++ b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst
@@ -0,0 +1,26 @@
+.. _probabilistic-road-map-(prm)-planning:
+
+Probabilistic Road-Map (PRM) planning
+-------------------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif
+
+This PRM planner uses Dijkstra method for graph search.
+
+In the animation, blue points are sampled points,
+
+Cyan crosses means searched points with Dijkstra method,
+
+The red line is the final path of PRM.
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.ProbabilisticRoadMap.probabilistic_road_map.prm_planning
+
+
+Reference
+~~~~~~~~~~~
+
+- `Probabilistic roadmap -
+ Wikipedia `__
diff --git a/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst
new file mode 100644
index 0000000000..c7bc3fb55c
--- /dev/null
+++ b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst
@@ -0,0 +1,111 @@
+
+Quintic polynomials planning
+----------------------------
+
+Motion planning with quintic polynomials.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/QuinticPolynomialsPlanner/animation.gif
+
+It can calculate 2D path, velocity, and acceleration profile based on
+quintic polynomials.
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathPlanning.QuinticPolynomialsPlanner.quintic_polynomials_planner.quintic_polynomials_planner
+
+
+
+Quintic polynomials for one dimensional robot motion
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+We assume a one-dimensional robot motion :math:`x(t)` at time :math:`t` is
+formulated as a quintic polynomials based on time as follows:
+
+.. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5
+ :label: quintic_eq1
+
+:math:`a_0, a_1. a_2, a_3, a_4, a_5` are parameters of the quintic polynomial.
+
+It is assumed that terminal states (start and end) are known as boundary conditions.
+
+Start position, velocity, and acceleration are :math:`x_s, v_s, a_s` respectively.
+
+End position, velocity, and acceleration are :math:`x_e, v_e, a_e` respectively.
+
+So, when time is 0.
+
+.. math:: x(0) = a_0 = x_s
+ :label: quintic_eq2
+
+Then, differentiating the equation :eq:`quintic_eq1` with t,
+
+.. math:: x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3+5a_5t^4
+ :label: quintic_eq3
+
+So, when time is 0,
+
+.. math:: x'(0) = a_1 = v_s
+ :label: quintic_eq4
+
+Then, differentiating the equation :eq:`quintic_eq3` with t again,
+
+.. math:: x''(t) = 2a_2+6a_3t+12a_4t^2
+ :label: quintic_eq5
+
+So, when time is 0,
+
+.. math:: x''(0) = 2a_2 = a_s
+ :label: quintic_eq6
+
+so, we can calculate :math:`a_0, a_1, a_2` with eq. :eq:`quintic_eq2`, :eq:`quintic_eq4`, :eq:`quintic_eq6` and boundary conditions.
+
+:math:`a_3, a_4, a_5` are still unknown in eq :eq:`quintic_eq1`.
+
+We assume that the end time for a maneuver is :math:`T`, we can get these equations from eq :eq:`quintic_eq1`, :eq:`quintic_eq3`, :eq:`quintic_eq5`:
+
+.. math:: x(T)=a_0+a_1T+a_2T^2+a_3T^3+a_4T^4+a_5T^5=x_e
+ :label: quintic_eq7
+
+.. math:: x'(T)=a_1+2a_2T+3a_3T^2+4a_4T^3+5a_5T^4=v_e
+ :label: quintic_eq8
+
+.. math:: x''(T)=2a_2+6a_3T+12a_4T^2+20a_5T^3=a_e
+ :label: quintic_eq9
+
+From eq :eq:`quintic_eq7`, :eq:`quintic_eq8`, :eq:`quintic_eq9`, we can calculate :math:`a_3, a_4, a_5` to solve the linear equations: :math:`Ax=b`
+
+.. math:: \begin{bmatrix} T^3 & T^4 & T^5 \\ 3T^2 & 4T^3 & 5T^4 \\ 6T & 12T^2 & 20T^3 \end{bmatrix}\begin{bmatrix} a_3\\ a_4\\ a_5\end{bmatrix}=\begin{bmatrix} x_e-x_s-v_sT-0.5a_sT^2\\ v_e-v_s-a_sT\\ a_e-a_s\end{bmatrix}
+
+We can get all unknown parameters now.
+
+Quintic polynomials for two dimensional robot motion (x-y)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+If you use two quintic polynomials along x axis and y axis, you can plan for two dimensional robot motion in x-y plane.
+
+.. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5
+ :label: quintic_eq10
+
+.. math:: y(t) = b_0+b_1t+b_2t^2+b_3t^3+b_4t^4+b_5t^5
+ :label: quintic_eq11
+
+It is assumed that terminal states (start and end) are known as boundary conditions.
+
+Start position, orientation, velocity, and acceleration are :math:`x_s, y_s, \theta_s, v_s, a_s` respectively.
+
+End position, orientation, velocity, and acceleration are :math:`x_e, y_e. \theta_e, v_e, a_e` respectively.
+
+Each velocity and acceleration boundary condition can be calculated with each orientation.
+
+:math:`v_{xs}=v_scos(\theta_s), v_{ys}=v_ssin(\theta_s)`
+
+:math:`v_{xe}=v_ecos(\theta_e), v_{ye}=v_esin(\theta_e)`
+
+Reference
+~~~~~~~~~~~
+
+- `Local Path Planning And Motion Control For Agv In
+ Positioning `__
+
+
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LR_L.png b/docs/modules/5_path_planning/reeds_shepp_path/LR_L.png
new file mode 100644
index 0000000000..1e64da57f2
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LR_L.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LR_LR.png b/docs/modules/5_path_planning/reeds_shepp_path/LR_LR.png
new file mode 100644
index 0000000000..e2c9883d8e
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LR_LR.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LSL.png b/docs/modules/5_path_planning/reeds_shepp_path/LSL.png
new file mode 100644
index 0000000000..6785ad3f8c
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LSL.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LSL90xR.png b/docs/modules/5_path_planning/reeds_shepp_path/LSL90xR.png
new file mode 100644
index 0000000000..54e892ba46
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LSL90xR.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LSR.png b/docs/modules/5_path_planning/reeds_shepp_path/LSR.png
new file mode 100644
index 0000000000..8acc0de69f
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LSR.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/LSR90_L.png b/docs/modules/5_path_planning/reeds_shepp_path/LSR90_L.png
new file mode 100644
index 0000000000..58d381010d
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/LSR90_L.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL.png
new file mode 100644
index 0000000000..c305c0be6e
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL90_R.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL90_R.png
new file mode 100644
index 0000000000..f2b38329da
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL90_R.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_R90SR.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SR.png
new file mode 100644
index 0000000000..4323a9fe3b
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SR.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_RL.png b/docs/modules/5_path_planning/reeds_shepp_path/L_RL.png
new file mode 100644
index 0000000000..ad58b8ffea
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_RL.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_RL_R.png b/docs/modules/5_path_planning/reeds_shepp_path/L_RL_R.png
new file mode 100644
index 0000000000..db4aaf6af3
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_RL_R.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/L_R_L.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R_L.png
new file mode 100644
index 0000000000..0d3082aeaf
Binary files /dev/null and b/docs/modules/5_path_planning/reeds_shepp_path/L_R_L.png differ
diff --git a/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst
new file mode 100644
index 0000000000..4dd54d7c97
--- /dev/null
+++ b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst
@@ -0,0 +1,399 @@
+Reeds Shepp planning
+--------------------
+
+A sample code with Reeds Shepp path planning.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true
+
+Code Link
+==============
+
+.. autofunction:: PathPlanning.ReedsSheppPath.reeds_shepp_path_planning.reeds_shepp_path_planning
+
+
+Mathematical Description of Individual Path Types
+=================================================
+Here is an overview of mathematical derivations of formulae for individual path types.
+
+In all the derivations below, radius of curvature of the vehicle is assumed to be of unit length and start pose is considered to be at origin. (*In code we are removing the offset due to start position and normalising the lengths before passing the values to these functions.*)
+
+Also, (t, u, v) respresent the measure of each motion requried. Thus, in case of a turning maneuver, they represent the angle inscribed at the centre of turning circle and in case of straight maneuver, they represent the distance to be travelled.
+
+1. **Left-Straight-Left**
+
+.. image:: LSL.png
+
+We can deduce the following facts using geometry.
+
+- AGHC is a rectangle.
+- :math:`∠LAC = ∠BAG = t`
+- :math:`t + v = φ`
+- :math:`C(x - sin(φ), y + cos(φ))`
+- :math:`A(0, 1)`
+- :math:`u, t = polar(vector)`
+
+Hence, we have:
+
+- :math:`u, t = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`v = φ - t`
+
+
+2. **Left-Straight-Right**
+
+.. image:: LSR.png
+
+With followng notations:
+
+- :math:`∠MBD = t1`
+- :math:`∠BDF = θ`
+- :math:`BC = u1`
+
+We can deduce the following facts using geometry.
+
+- D is mid-point of BC and FG.
+- :math:`t - v = φ`
+- :math:`C(x + sin(φ), y - cos(φ))`
+- :math:`A(0, 1)`
+- :math:`u1, t1 = polar(vector)`
+- :math:`\frac{u1^2}{4} = 1 + \frac{u^2}{4}`
+- :math:`BF = 1` [Radius Of Curvature]
+- :math:`FD = \frac{u}{2}`
+- :math:`θ = arctan(\frac{BF}{FD})`
+- :math:`t1 + θ = t`
+
+Hence, we have:
+
+- :math:`u1, t1 = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = \sqrt{u1^2 - 4}`
+- :math:`θ = arctan(\frac{2}{u})`
+- :math:`t = t1 + θ`
+- :math:`v = t - φ`
+
+3. **LeftxRightxLeft**
+
+.. image:: L_R_L.png
+
+With followng notations:
+
+- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle]
+- :math:`∠DBK = θ`
+- :math:`BD = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t + u + v = φ`
+- :math:`D(x - sin(φ), y + cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`A = arccos(\frac{BD/2}{CD})`
+- :math:`u = (π - 2*A)`
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`∠KBD = θ`
+- :math:`t = ∠ABK + ∠KBD + ∠DBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`A = arccos(\frac{u1/2}{2})`
+- :math:`t = \frac{π}{2} + θ + A`
+- :math:`u = (π - 2*A)`
+- :math:`v = (φ - t - u)`
+
+4. **LeftxRight-Left**
+
+.. image:: L_RL.png
+
+With followng notations:
+
+- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle]
+- :math:`∠DBK = θ`
+- :math:`BD = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t + u - v = φ`
+- :math:`D(x - sin(φ), y + cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`A = arccos(\frac{BD/2}{CD})`
+- :math:`u = (π - 2*A)`
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`∠KBD = θ`
+- :math:`t = ∠ABK + ∠KBD + ∠DBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`A = arccos(\frac{u1/2}{2})`
+- :math:`t = \frac{π}{2} + θ + A`
+- :math:`u = (π - 2*A)`
+- :math:`v = (-φ + t + u)`
+
+5. **Left-RightxLeft**
+
+.. image:: LR_L.png
+
+With followng notations:
+
+- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle]
+- :math:`∠DBK = θ`
+- :math:`BD = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - u - v = φ`
+- :math:`D(x - sin(φ), y + cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`BC = CD = 2` [2 * radius of curvature]
+- :math:`cos(2π - u) = \frac{BC^2 + CD^2 - BD^2}{2 * BC * CD}` [Cosine Rule]
+- :math:`\frac{sin(A)}{BC} = \frac{sin(u)}{u1}` [Sine Rule]
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`∠KBD = θ`
+- :math:`t = ∠ABK + ∠KBD - ∠DBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`u = arccos(1 - \frac{u1^2}{8})`
+- :math:`A = arcsin(\frac{sin(u)}{u1}*2)`
+- :math:`t = \frac{π}{2} + θ - A`
+- :math:`v = (t - u - φ)`
+
+6. **Left-RightxLeft-Right**
+
+.. image:: LR_LR.png
+
+With followng notations:
+
+- :math:`∠CLG = ∠BCL = ∠CBG = ∠LGB = A = u` [BGCL is an isoceles trapezium]
+- :math:`∠KBG = θ`
+- :math:`BG = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - 2u + v = φ`
+- :math:`G(x + sin(φ), y - cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`BC = CL = LG = 2` [2 * radius of curvature]
+- :math:`CG^2 = CL^2 + LG^2 - 2*CL*LG*cos(A)` [Cosine rule in LGC]
+- :math:`CG^2 = CL^2 + LG^2 - 2*CL*LG*cos(A)` [Cosine rule in LGC]
+- From the previous two equations: :math:`A = arccos(\frac{u1 + 2}{4})`
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`t = ∠ABK + ∠KBG + ∠GBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = arccos(\frac{u1 + 2}{4})`
+- :math:`t = \frac{π}{2} + θ + u`
+- :math:`v = (φ - t + 2u)`
+
+7. **LeftxRight-LeftxRight**
+
+.. image:: L_RL_R.png
+
+With followng notations:
+
+- :math:`∠GBC = A` [BGCL is an isoceles trapezium]
+- :math:`∠KBG = θ`
+- :math:`BG = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - v = φ`
+- :math:`G(x + sin(φ), y - cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`BC = CL = LG = 2` [2 * radius of curvature]
+- :math:`CD = 1` [radius of curvature]
+- D is midpoint of BG
+- :math:`BD = \frac{u1}{2}`
+- :math:`cos(u) = \frac{BC^2 + CD^2 - BD^2}{2*BC*CD}` [Cosine rule in BCD]
+- :math:`sin(A) = CD*\frac{sin(u)}{BD}` [Sine rule in BCD]
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`t = ∠ABK + ∠KBG + ∠GBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = arccos(\frac{20 - u1^2}{16})`
+- :math:`A = arcsin(2*\frac{sin(u)}{u1})`
+- :math:`t = \frac{π}{2} + θ + A`
+- :math:`v = (t - φ)`
+
+
+8. **LeftxRight90-Straight-Left**
+
+.. image:: L_R90SL.png
+
+With followng notations:
+
+- :math:`∠FBM = A` [BGCL is an isoceles trapezium]
+- :math:`∠KBF = θ`
+- :math:`BF = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t + \frac{π}{2} - v = φ`
+- :math:`F(x - sin(φ), y + cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`BM = CB = 2` [2 * radius of curvature]
+- :math:`MD = CD = 1` [CGDM is a rectangle]
+- :math:`MC = GD = u` [CGDM is a rectangle]
+- :math:`MF = MD + DF = 2`
+- :math:`BM = \sqrt{BF^2 - MF^2}` [Pythagoras theorem on BFM]
+- :math:`tan(A) = \frac{MF}{BM}`
+- :math:`u = MC = BM - CB`
+- :math:`t = ∠ABK + ∠KBF + ∠FBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`u = arccos(\sqrt{u1^2 - 4} - 2)`
+- :math:`A = arctan(\frac{2}{\sqrt{u1^2 - 4}})`
+- :math:`t = \frac{π}{2} + θ + A`
+- :math:`v = (t - φ + \frac{π}{2})`
+
+
+9. **Left-Straight-Right90xLeft**
+
+.. image:: LSR90_L.png
+
+With followng notations:
+
+- :math:`∠MBH = A` [BGCL is an isoceles trapezium]
+- :math:`∠KBH = θ`
+- :math:`BH = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - \frac{π}{2} - v = φ`
+- :math:`H(x - sin(φ), y + cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`GH = 2` [2 * radius of curvature]
+- :math:`CM = DG = 1` [CGDM is a rectangle]
+- :math:`CD = MG = u` [CGDM is a rectangle]
+- :math:`BM = BC + CM = 2`
+- :math:`MH = \sqrt{BH^2 - BM^2}` [Pythagoras theorem on BHM]
+- :math:`tan(A) = \frac{HM}{BM}`
+- :math:`u = MC = BM - CB`
+- :math:`t = ∠ABK + ∠KBH - ∠HBC`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)`
+- :math:`u = arccos(\sqrt{u1^2 - 4} - 2)`
+- :math:`A = arctan(\frac{2}{\sqrt{u1^2 - 4}})`
+- :math:`t = \frac{π}{2} + θ - A`
+- :math:`v = (t - φ - \frac{π}{2})`
+
+
+10. **LeftxRight90-Straight-Right**
+
+.. image:: L_R90SR.png
+
+With followng notations:
+
+- :math:`∠KBG = θ`
+- :math:`BG = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - \frac{π}{2} - v = φ`
+- :math:`G(x + sin(φ), y - cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`BD = 2` [2 * radius of curvature]
+- :math:`DG = EF = u` [DGFE is a rectangle]
+- :math:`DG = BG - BD = 2`
+- :math:`∠ABK = \frac{π}{2}`
+- :math:`t = ∠ABK + ∠KBG`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = u1 - 2`
+- :math:`t = \frac{π}{2} + θ`
+- :math:`v = (t - φ - \frac{π}{2})`
+
+
+11. **Left-Straight-Left90xRight**
+
+.. image:: LSL90xR.png
+
+With followng notations:
+
+- :math:`∠KBH = θ`
+- :math:`BH = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t + \frac{π}{2} + v = φ`
+- :math:`H(x + sin(φ), y - cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`GH = 2` [2 * radius of curvature]
+- :math:`DC = BG = u` [DGBC is a rectangle]
+- :math:`BG = BH - GH`
+- :math:`∠ABC= ∠KBH`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = u1 - 2`
+- :math:`t = θ`
+- :math:`v = (φ - t - \frac{π}{2})`
+
+
+12. **LeftxRight90-Straight-Left90xRight**
+
+.. image:: L_R90SL90_R.png
+
+With followng notations:
+
+- :math:`∠KBH = θ`
+- :math:`∠HBM = A`
+- :math:`BH = u1`
+
+We can deduce the following facts using geometry.
+
+- :math:`t - v = φ`
+- :math:`H(x + sin(φ), y - cos(φ))`
+- :math:`B(0, 1)`
+- :math:`u1, θ = polar(vector)`
+- :math:`GF = ED = 1` [radius of curvature]
+- :math:`BD = GH = 2` [2 * radius of curvature]
+- :math:`FN = GH = 2` [ENMD is a rectangle]
+- :math:`NH = GF = 1` [FNHG is a rectangle]
+- :math:`MN = ED = 1` [ENMD is a rectangle]
+- :math:`DO = EF = u` [DOFE is a rectangle]
+- :math:`MH = MN + NH = 2`
+- :math:`BM = \sqrt{BH^2 - MH^2}` [Pythagoras theorem on BHM]
+- :math:`DO = BM - BD - OM`
+- :math:`tan(A) = \frac{MH}{BM}`
+- :math:`∠ABC = ∠ABK + ∠KBH + ∠HBM`
+
+Hence, we have:
+
+- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)`
+- :math:`u = /sqrt{u1^2 - 4} - 4`
+- :math:`A = arctan(\frac{2}{u1^2 - 4})`
+- :math:`t = \frac{π}{2} + θ + A`
+- :math:`v = (t - φ)`
+
+
+Reference
+=============
+
+- `15.3.2 Reeds-Shepp
+ Curves `__
+
+- `optimal paths for a car that goes both forwards and
+ backwards `__
+
+- `ghliu/pyReedsShepp: Implementation of Reeds Shepp
+ curve. `__
diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_1.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_1.png
similarity index 100%
rename from PathPlanning/ClosedLoopRRTStar/Figure_1.png
rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_1.png
diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_3.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_3.png
similarity index 100%
rename from PathPlanning/ClosedLoopRRTStar/Figure_3.png
rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_3.png
diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_4.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_4.png
similarity index 100%
rename from PathPlanning/ClosedLoopRRTStar/Figure_4.png
rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_4.png
diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_5.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_5.png
similarity index 100%
rename from PathPlanning/ClosedLoopRRTStar/Figure_5.png
rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_5.png
diff --git a/PathPlanning/RRT/figure_1.png b/docs/modules/5_path_planning/rrt/figure_1.png
similarity index 100%
rename from PathPlanning/RRT/figure_1.png
rename to docs/modules/5_path_planning/rrt/figure_1.png
diff --git a/docs/modules/5_path_planning/rrt/rrt_main.rst b/docs/modules/5_path_planning/rrt/rrt_main.rst
new file mode 100644
index 0000000000..1bd5497f4c
--- /dev/null
+++ b/docs/modules/5_path_planning/rrt/rrt_main.rst
@@ -0,0 +1,172 @@
+.. _rapidly-exploring-random-trees-(rrt):
+
+Rapidly-Exploring Random Trees (RRT)
+------------------------------------
+
+Basic RRT
+~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif
+
+This is a simple path planning code with Rapidly-Exploring Random Trees
+(RRT)
+
+Black circles are obstacles, green line is a searched tree, red crosses
+are start and goal positions.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.RRT.rrt.RRT
+
+
+.. include:: rrt_star.rst
+
+
+RRT with dubins path
+~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif
+
+Path planning for a car robot with RRT and dubins path planner.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.RRTDubins.rrt_dubins.RRTDubins
+
+
+.. _rrt*-with-dubins-path:
+
+RRT\* with dubins path
+~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif
+
+Path planning for a car robot with RRT\* and dubins path planner.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.RRTStarDubins.rrt_star_dubins.RRTStarDubins
+
+
+.. _rrt*-with-reeds-sheep-path:
+
+RRT\* with reeds-sheep path
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif
+
+Path planning for a car robot with RRT\* and reeds sheep path planner.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.RRTStarReedsShepp.rrt_star_reeds_shepp.RRTStarReedsShepp
+
+
+.. _informed-rrt*:
+
+Informed RRT\*
+~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif
+
+This is a path planning code with Informed RRT*.
+
+The cyan ellipse is the heuristic sampling domain of Informed RRT*.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.InformedRRTStar.informed_rrt_star.InformedRRTStar
+
+
+Reference
+^^^^^^^^^^
+
+- `Informed RRT\*: Optimal Sampling-based Path Planning Focused via
+ Direct Sampling of an Admissible Ellipsoidal
+ Heuristic `__
+
+.. _batch-informed-rrt*:
+
+Batch Informed RRT\*
+~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif
+
+This is a path planning code with Batch Informed RRT*.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.BatchInformedRRTStar.batch_informed_rrt_star.BITStar
+
+
+Reference
+^^^^^^^^^^^
+
+- `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the
+ Heuristically Guided Search of Implicit Random Geometric
+ Graphs `__
+
+
+.. _closed-loop-rrt*:
+
+Closed Loop RRT\*
+~~~~~~~~~~~~~~~~~
+
+A vehicle model based path planning with closed loop RRT*.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif
+
+In this code, pure-pursuit algorithm is used for steering control,
+
+PID is used for speed control.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.ClosedLoopRRTStar.closed_loop_rrt_star_car.ClosedLoopRRTStar
+
+
+Reference
+^^^^^^^^^^^^
+
+- `Motion Planning in Complex Environments using Closed-loop
+ Prediction `__
+
+- `Real-time Motion Planning with Applications to Autonomous Urban
+ Driving `__
+
+- `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning
+ Using Closed-loop Prediction `__
+
+
+.. _lqr-rrt*:
+
+LQR-RRT\*
+~~~~~~~~~
+
+This is a path planning simulation with LQR-RRT*.
+
+A double integrator motion model is used for LQR local planner.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.LQRRRTStar.lqr_rrt_star.LQRRRTStar
+
+
+Reference
+~~~~~~~~~~~~~
+
+- `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically
+ Derived Extension
+ Heuristics `__
+
+- `MahanFathi/LQR-RRTstar: LQR-RRT\* method is used for random motion planning of a simple pendulum in its phase plot `__
\ No newline at end of file
diff --git a/docs/modules/5_path_planning/rrt/rrt_star.rst b/docs/modules/5_path_planning/rrt/rrt_star.rst
new file mode 100644
index 0000000000..960b9976d5
--- /dev/null
+++ b/docs/modules/5_path_planning/rrt/rrt_star.rst
@@ -0,0 +1,27 @@
+RRT\*
+~~~~~
+
+.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif
+
+This is a path planning code with RRT\*
+
+Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions.
+
+Code Link
+^^^^^^^^^^
+
+.. autoclass:: PathPlanning.RRTStar.rrt_star.RRTStar
+
+
+Simulation
+^^^^^^^^^^
+
+.. image:: rrt_star/rrt_star_1_0.png
+ :width: 600px
+
+
+Ref
+^^^
+- `Sampling-based Algorithms for Optimal Motion Planning `__
+- `Incremental Sampling-based Algorithms for Optimal Motion Planning `__
+
diff --git a/docs/modules/rrt_star_files/rrt_star_1_0.png b/docs/modules/5_path_planning/rrt/rrt_star/rrt_star_1_0.png
similarity index 100%
rename from docs/modules/rrt_star_files/rrt_star_1_0.png
rename to docs/modules/5_path_planning/rrt/rrt_star/rrt_star_1_0.png
diff --git a/PathPlanning/RRTStarReedsShepp/figure_1.png b/docs/modules/5_path_planning/rrt/rrt_star_reeds_shepp/figure_1.png
similarity index 100%
rename from PathPlanning/RRTStarReedsShepp/figure_1.png
rename to docs/modules/5_path_planning/rrt/rrt_star_reeds_shepp/figure_1.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_1.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_1.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_1.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_1.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_2.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_2.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_2.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_2.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_3.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_3.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_3.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_3.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_4.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_4.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_4.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_4.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_5.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_5.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_5.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_5.png
diff --git a/PathPlanning/StateLatticePlanner/Figure_6.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_6.png
similarity index 100%
rename from PathPlanning/StateLatticePlanner/Figure_6.png
rename to docs/modules/5_path_planning/state_lattice_planner/Figure_6.png
diff --git a/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst
new file mode 100644
index 0000000000..9f8cc0c50f
--- /dev/null
+++ b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst
@@ -0,0 +1,50 @@
+State Lattice Planning
+----------------------
+
+This script is a path planning code with state lattice planning.
+
+This code uses the model predictive trajectory generator to solve
+boundary problem.
+
+
+Uniform polar sampling
+~~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif
+
+Code Link
+^^^^^^^^^^^^^
+
+.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_uniform_polar_states
+
+
+Biased polar sampling
+~~~~~~~~~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif
+
+Code Link
+^^^^^^^^^^^^^
+.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_biased_polar_states
+
+
+Lane sampling
+~~~~~~~~~~~~~
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif
+
+Code Link
+^^^^^^^^^^^^^
+.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_lane_states
+
+
+Reference
+~~~~~~~~~~~~~~~
+
+- `Optimal rough terrain trajectory generation for wheeled mobile
+ robots `__
+
+- `State Space Sampling of Feasible Motions for High-Performance Mobile
+ Robot Navigation in Complex
+ Environments `__
+
diff --git a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst
new file mode 100644
index 0000000000..a44dd20a97
--- /dev/null
+++ b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst
@@ -0,0 +1,108 @@
+Time based grid search
+----------------------
+
+Space-time astar
+~~~~~~~~~~~~~~~~~~~~~~
+
+This is an extension of A* algorithm that supports planning around dynamic obstacles.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar/path_animation.gif
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar/path_animation2.gif
+
+The key difference of this algorithm compared to vanilla A* is that the cost and heuristic are now time-based instead of distance-based.
+Using a time-based cost and heuristic ensures the path found is optimal in terms of time to reach the goal.
+
+The cost is the amount of time it takes to reach a given node, and the heuristic is the minimum amount of time it could take to reach the goal from that node, disregarding all obstacles.
+For a simple scenario where the robot can move 1 cell per time step and stop and go as it pleases, the heuristic for time is equivalent to the heuristic for distance.
+
+One optimization that was added in `this PR `__ was to add an expanded set to the algorithm. The algorithm will not expand nodes that are already in that set. This greatly reduces the number of node expansions needed to find a path, since no duplicates are expanded. It also helps to reduce the amount of memory the algorithm uses.
+
+Before::
+
+ Found path to goal after 204490 expansions
+ Planning took: 1.72464 seconds
+ Memory usage (RSS): 68.19 MB
+
+
+After::
+
+ Found path to goal after 2348 expansions
+ Planning took: 0.01550 seconds
+ Memory usage (RSS): 64.85 MB
+
+When starting at (1, 11) in the structured obstacle arrangement (second of the two gifs above).
+
+Code Link
+^^^^^^^^^^^^^
+.. autoclass:: PathPlanning.TimeBasedPathPlanning.SpaceTimeAStar.SpaceTimeAStar
+
+
+Safe Interval Path Planning
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The safe interval path planning algorithm is described in this paper:
+
+`SIPP: Safe Interval Path Planning for Dynamic Environments `__
+
+It is faster than space-time A* because it pre-computes the intervals of time that are unoccupied in each cell. This allows it to reduce the number of successor node it generates by avoiding nodes within the same interval.
+
+**Comparison with SpaceTime A*:**
+
+Arrangement 1 starting at (1, 18)
+
+SafeInterval planner::
+
+ Found path to goal after 322 expansions
+ Planning took: 0.00730 seconds
+
+SpaceTime A*::
+
+ Found path to goal after 2717154 expansions
+ Planning took: 20.51330 seconds
+
+**Benchmarking the Safe Interval Path Planner:**
+
+250 random obstacles::
+
+ Found path to goal after 764 expansions
+ Planning took: 0.60596 seconds
+
+.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/SafeIntervalPathPlanner/path_animation.gif
+
+Arrangement 1 starting at (1, 18)::
+
+ Found path to goal after 322 expansions
+ Planning took: 0.00730 seconds
+
+.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/SafeIntervalPathPlanner/path_animation2.gif
+
+Code Link
+^^^^^^^^^^^^^
+.. autoclass:: PathPlanning.TimeBasedPathPlanning.SafeInterval.SafeIntervalPathPlanner
+
+Multi-Agent Path Planning
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Priority Based Planning
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+The planner generates an order to plan in, and generates plans for the robots in that order. Each planned path is reserved in the grid, and all future plans must avoid that path. The robots are planned for in descending order of distance from start to goal.
+
+This is a sub-optimal algorithm because no replanning happens once paths are found. It does not guarantee the shortest path is found for any particular robot, nor that the final set of paths found contains the lowest possible amount of time or movement.
+
+Static Obstacles:
+
+.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/PriorityBasedPlanner/priority_planner2.gif
+
+Dynamic Obstacles:
+
+.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/PriorityBasedPlanner/priority_planner.gif
+
+
+References
+~~~~~~~~~~~
+
+- `Cooperative Pathfinding `__
+- `SIPP: Safe Interval Path Planning for Dynamic Environments `__
+- `Prioritized Planning Algorithms for Trajectory Coordination of Multiple Mobile Robots `__
\ No newline at end of file
diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/step0.png b/docs/modules/5_path_planning/visibility_road_map_planner/step0.png
new file mode 100644
index 0000000000..4e672720f6
Binary files /dev/null and b/docs/modules/5_path_planning/visibility_road_map_planner/step0.png differ
diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/step1.png b/docs/modules/5_path_planning/visibility_road_map_planner/step1.png
new file mode 100644
index 0000000000..e70395241e
Binary files /dev/null and b/docs/modules/5_path_planning/visibility_road_map_planner/step1.png differ
diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/step2.png b/docs/modules/5_path_planning/visibility_road_map_planner/step2.png
new file mode 100644
index 0000000000..7aa7b025e0
Binary files /dev/null and b/docs/modules/5_path_planning/visibility_road_map_planner/step2.png differ
diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/step3.png b/docs/modules/5_path_planning/visibility_road_map_planner/step3.png
new file mode 100644
index 0000000000..73ffc586c1
Binary files /dev/null and b/docs/modules/5_path_planning/visibility_road_map_planner/step3.png differ
diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst b/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst
new file mode 100644
index 0000000000..aac96d6e19
--- /dev/null
+++ b/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst
@@ -0,0 +1,76 @@
+Visibility Road-Map planner
+---------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VisibilityRoadMap/animation.gif
+
+`[Code] `_
+
+This visibility road-map planner uses Dijkstra method for graph search.
+
+In the animation, the black lines are polygon obstacles,
+
+red crosses are visibility nodes, and blue lines area collision free visibility graphs.
+
+The red line is the final path searched by dijkstra algorithm frm the visibility graphs.
+
+Code Link
+~~~~~~~~~~~~
+.. autoclass:: PathPlanning.VisibilityRoadMap.visibility_road_map.VisibilityRoadMap
+
+
+Algorithms
+~~~~~~~~~~
+
+In this chapter, how does the visibility road map planner search a path.
+
+We assume this planner can be provided these information in the below figure.
+
+- 1. Start point (Red point)
+- 2. Goal point (Blue point)
+- 3. Obstacle polygons (Black lines)
+
+.. image:: step0.png
+ :width: 400px
+
+
+Step1: Generate visibility nodes based on polygon obstacles
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+The nodes are generated by expanded these polygons vertexes like the below figure:
+
+.. image:: step1.png
+ :width: 400px
+
+Each polygon vertex is expanded outward from the vector of adjacent vertices.
+
+The start and goal point are included as nodes as well.
+
+Step2: Generate visibility graphs connecting the nodes.
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+When connecting the nodes, the arc between two nodes is checked to collided or not to each obstacles.
+
+If the arc is collided, the graph is removed.
+
+The blue lines are generated visibility graphs in the figure:
+
+.. image:: step2.png
+ :width: 400px
+
+
+Step3: Search the shortest path in the graphs using Dijkstra algorithm
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+The red line is searched path in the figure:
+
+.. image:: step3.png
+ :width: 400px
+
+You can find the details of Dijkstra algorithm in :ref:`dijkstra`.
+
+References
+~~~~~~~~~~~~
+
+- `Visibility graph - Wikipedia `_
+
+
diff --git a/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst
new file mode 100644
index 0000000000..a9a41aab74
--- /dev/null
+++ b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst
@@ -0,0 +1,23 @@
+Voronoi Road-Map planning
+-------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif
+
+This Voronoi road-map planner uses Dijkstra method for graph search.
+
+In the animation, blue points are Voronoi points,
+
+Cyan crosses mean searched points with Dijkstra method,
+
+The red line is the final path of Vornoi Road-Map.
+
+Code Link
+~~~~~~~~~~~~~~~
+.. autoclass:: PathPlanning.VoronoiRoadMap.voronoi_road_map.VoronoiRoadMapPlanner
+
+
+Reference
+~~~~~~~~~~~~
+
+- `Robotic Motion Planning `__
+
diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_1_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png
similarity index 100%
rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_1_0.png
rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png
diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_2_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png
similarity index 100%
rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_2_0.png
rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png
diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_3_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png
similarity index 100%
rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_3_0.png
rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png
diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_4_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png
similarity index 100%
rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_4_0.png
rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png
diff --git a/docs/modules/cgmres_nmpc.rst b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst
similarity index 77%
rename from docs/modules/cgmres_nmpc.rst
rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst
index a6959e7262..914a4555ff 100644
--- a/docs/modules/cgmres_nmpc.rst
+++ b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst
@@ -2,59 +2,25 @@
Nonlinear Model Predictive Control with C-GMRES
-----------------------------------------------
-.. code-block:: ipython3
-
- from IPython.display import Image
- Image(filename="Figure_4.png",width=600)
-
-
-
-
-.. image:: cgmres_nmpc_files/cgmres_nmpc_1_0.png
+.. image:: cgmres_nmpc_1_0.png
:width: 600px
-
-
-.. code-block:: ipython3
-
- Image(filename="Figure_1.png",width=600)
-
-
-
-
-.. image:: cgmres_nmpc_files/cgmres_nmpc_2_0.png
+.. image:: cgmres_nmpc_2_0.png
:width: 600px
-
-
-.. code-block:: ipython3
-
- Image(filename="Figure_2.png",width=600)
-
-
-
-
-.. image:: cgmres_nmpc_files/cgmres_nmpc_3_0.png
+.. image:: cgmres_nmpc_3_0.png
:width: 600px
-
-
-.. code-block:: ipython3
-
- Image(filename="Figure_3.png",width=600)
-
-
-
-
-.. image:: cgmres_nmpc_files/cgmres_nmpc_4_0.png
+.. image:: cgmres_nmpc_4_0.png
:width: 600px
-
-
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif
:alt: gif
- gif
+Code Link
+~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.cgmres_nmpc.cgmres_nmpc.NMPCControllerCGMRES
Mathematical Formulation
~~~~~~~~~~~~~~~~~~~~~~~~
@@ -99,7 +65,7 @@ Ref
- `Shunichi09/nonlinear_control: Implementing the nonlinear model
predictive control, sliding mode
- control `__
+ control `__
- `非線形モデル予測制御におけるCGMRES法をpythonで実装する -
Qiita `__
diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst
new file mode 100644
index 0000000000..b0ba9e0d45
--- /dev/null
+++ b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst
@@ -0,0 +1,145 @@
+.. _linearquadratic-regulator-(lqr)-speed-and-steering-control:
+
+Linear–quadratic regulator (LQR) speed and steering control
+-----------------------------------------------------------
+
+Path tracking simulation with LQR speed and steering control.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif
+
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.lqr_speed_steer_control.lqr_speed_steer_control.lqr_speed_steering_control
+
+
+Overview
+~~~~~~~~
+
+The LQR (Linear Quadratic Regulator) speed and steering control model implemented in `lqr_speed_steer_control.py` provides a simulation
+for an autonomous vehicle to track:
+
+1. A desired speed by adjusting acceleration based on feedback from the current state and the desired speed.
+
+2. A desired trajectory by adjusting steering angle based on feedback from the current state and the desired trajectory.
+
+by only using one LQT controller.
+
+Vehicle motion Model
+~~~~~~~~~~~~~~~~~~~~~
+
+The below figure shows the geometric model of the vehicle used in this simulation:
+
+.. image:: lqr_steering_control_model.jpg
+ :width: 600px
+
+The `e`, :math:`{\theta}`, and :math:`\upsilon` represent the lateral error, orientation error, and velocity error, respectively, with respect to the desired trajectory and speed.
+And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors.
+
+The :math:`e_t` and :math:`\theta_t`, and :math:`\upsilon` are the updated values of `e`, :math:`\theta`, :math:`\upsilon` and at time `t`, respectively, and can be calculated using the following kinematic equations:
+
+.. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt
+
+.. math:: \theta_t = \theta_{t-1} + \dot{\theta}_{t-1} dt
+
+.. math:: \upsilon_t = \upsilon_{t-1} + a_{t-1} dt
+
+Where `dt` is the time difference and :math:`a_t` is the acceleration at the time `t`.
+
+The change rate of the `e` can be calculated as:
+
+.. math:: \dot{e}_t = V \sin(\theta_{t-1})
+
+Where `V` is the current vehicle speed.
+
+If the :math:`\theta` is small,
+
+.. math:: \theta \approx 0
+
+the :math:`\sin(\theta)` can be approximated as :math:`\theta`:
+
+.. math:: \sin(\theta) = \theta
+
+So, the change rate of the `e` can be approximated as:
+
+.. math:: \dot{e}_t = V \theta_{t-1}
+
+The change rate of the :math:`\theta` can be calculated as:
+
+.. math:: \dot{\theta}_t = \frac{V}{L} \tan(\delta)
+
+where `L` is the wheelbase of the vehicle and :math:`\delta` is the steering angle.
+
+If the :math:`\delta` is small,
+
+.. math:: \delta \approx 0
+
+the :math:`\tan(\delta)` can be approximated as :math:`\delta`:
+
+.. math:: \tan(\delta) = \delta
+
+So, the change rate of the :math:`\theta` can be approximated as:
+
+.. math:: \dot{\theta}_t = \frac{V}{L} \delta
+
+The above equations can be used to update the state of the vehicle at each time step.
+
+Control Model
+~~~~~~~~~~~~~~
+
+To formulate the state-space representation of the vehicle dynamics as a linear model,
+the state vector `x` and control input vector `u` are defined as follows:
+
+.. math:: x_t = [e_t, \dot{e}_t, \theta_t, \dot{\theta}_t, \upsilon_t]^T
+
+.. math:: u_t = [\delta_t, a_t]^T
+
+The linear state transition equation can be represented as:
+
+.. math:: x_{t+1} = A x_t + B u_t
+
+where:
+
+:math:`\begin{equation*} A = \begin{bmatrix} 1 & dt & 0 & 0 & 0\\ 0 & 0 & v & 0 & 0\\ 0 & 0 & 1 & dt & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 1\\\end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} B = \begin{bmatrix} 0 & 0\\ 0 & 0\\ 0 & 0\\ \frac{v}{L} & 0\\ 0 & dt \\ \end{bmatrix} \end{equation*}`
+
+LQR controller
+~~~~~~~~~~~~~~~
+
+The Linear Quadratic Regulator (LQR) controller is used to calculate the optimal control input `u` that minimizes the quadratic cost function:
+
+:math:`J = \sum_{t=0}^{N} (x_t^T Q x_t + u_t^T R u_t)`
+
+where `Q` and `R` are the weighting matrices for the state and control input, respectively.
+
+for the linear model:
+
+:math:`x_{t+1} = A x_t + B u_t`
+
+The optimal control input `u` can be calculated as:
+
+:math:`u_t = -K x_t`
+
+where `K` is the feedback gain matrix obtained by solving the Riccati equation.
+
+Simulation results
+~~~~~~~~~~~~~~~~~~~
+
+
+.. image:: x-y.png
+ :width: 600px
+
+.. image:: yaw.png
+ :width: 600px
+
+.. image:: speed.png
+ :width: 600px
+
+
+
+Reference
+~~~~~~~~~~~
+
+- `Towards fully autonomous driving: Systems and algorithms `__
diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg
new file mode 100644
index 0000000000..83754d5bb0
Binary files /dev/null and b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg differ
diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/speed.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/speed.png
new file mode 100644
index 0000000000..ae99eb7ea3
Binary files /dev/null and b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/speed.png differ
diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/x-y.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/x-y.png
new file mode 100644
index 0000000000..bff3f1a786
Binary files /dev/null and b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/x-y.png differ
diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/yaw.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/yaw.png
new file mode 100644
index 0000000000..7f3d9c1d10
Binary files /dev/null and b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/yaw.png differ
diff --git a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst
new file mode 100644
index 0000000000..fc8f2a33aa
--- /dev/null
+++ b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst
@@ -0,0 +1,125 @@
+.. _linearquadratic-regulator-(lqr)-steering-control:
+
+Linear–quadratic regulator (LQR) steering control
+-------------------------------------------------
+
+Path tracking simulation with LQR steering control and PID speed
+control.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.lqr_steer_control.lqr_steer_control.lqr_steering_control
+
+
+Overview
+~~~~~~~~
+
+The LQR (Linear Quadratic Regulator) steering control model implemented in lqr_steer_control.py provides a simulation
+for an autonomous vehicle to track a desired trajectory by adjusting steering angle based on feedback from the current state and the desired trajectory.
+This model utilizes a combination of PID speed control and LQR steering control to achieve smooth and accurate trajectory tracking.
+
+Vehicle motion Model
+~~~~~~~~~~~~~~~~~~~~~
+
+The below figure shows the geometric model of the vehicle used in this simulation:
+
+.. image:: lqr_steering_control_model.jpg
+ :width: 600px
+
+The `e` and :math:`\theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory.
+And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors.
+
+The :math:`e_t` and :math:`\theta_t` are the updated values of `e` and :math:`\theta` at time `t`, respectively, and can be calculated using the following kinematic equations:
+
+.. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt
+
+.. math:: \theta_t = \theta_{t-1} + \dot{\theta}_{t-1} dt
+
+Where `dt` is the time difference.
+
+The change rate of the `e` can be calculated as:
+
+.. math:: \dot{e}_t = V \sin(\theta_{t-1})
+
+Where `V` is the current vehicle speed.
+
+If the :math:`\theta` is small,
+
+.. math:: \theta \approx 0
+
+the :math:`\sin(\theta)` can be approximated as :math:`\theta`:
+
+.. math:: \sin(\theta) = \theta
+
+So, the change rate of the `e` can be approximated as:
+
+.. math:: \dot{e}_t = V \theta_{t-1}
+
+The change rate of the :math:`\theta` can be calculated as:
+
+.. math:: \dot{\theta}_t = \frac{V}{L} \tan(\delta)
+
+where `L` is the wheelbase of the vehicle and :math:`\delta` is the steering angle.
+
+If the :math:`\delta` is small,
+
+.. math:: \delta \approx 0
+
+the :math:`\tan(\delta)` can be approximated as :math:`\delta`:
+
+.. math:: \tan(\delta) = \delta
+
+So, the change rate of the :math:`\theta` can be approximated as:
+
+.. math:: \dot{\theta}_t = \frac{V}{L} \delta
+
+The above equations can be used to update the state of the vehicle at each time step.
+
+Control Model
+~~~~~~~~~~~~~~
+
+To formulate the state-space representation of the vehicle dynamics as a linear model,
+the state vector `x` and control input vector `u` are defined as follows:
+
+.. math:: x_t = [e_t, \dot{e}_t, \theta_t, \dot{\theta}_t]^T
+
+.. math:: u_t = \delta_t
+
+The linear state transition equation can be represented as:
+
+.. math:: x_{t+1} = A x_t + B u_t
+
+where:
+
+:math:`\begin{equation*} A = \begin{bmatrix} 1 & dt & 0 & 0\\ 0 & 0 & v & 0\\ 0 & 0 & 1 & dt\\ 0 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
+
+:math:`\begin{equation*} B = \begin{bmatrix} 0\\ 0\\ 0\\ \frac{v}{L} \\ \end{bmatrix} \end{equation*}`
+
+LQR controller
+~~~~~~~~~~~~~~~
+
+The Linear Quadratic Regulator (LQR) controller is used to calculate the optimal control input `u` that minimizes the quadratic cost function:
+
+:math:`J = \sum_{t=0}^{N} (x_t^T Q x_t + u_t^T R u_t)`
+
+where `Q` and `R` are the weighting matrices for the state and control input, respectively.
+
+for the linear model:
+
+:math:`x_{t+1} = A x_t + B u_t`
+
+The optimal control input `u` can be calculated as:
+
+:math:`u_t = -K x_t`
+
+where `K` is the feedback gain matrix obtained by solving the Riccati equation.
+
+Reference
+~~~~~~~~~~~
+- `ApolloAuto/apollo: An open autonomous driving platform `_
+
+- `Linear Quadratic Regulator (LQR) `_
+
diff --git a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_model.jpg b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_model.jpg
new file mode 100644
index 0000000000..83754d5bb0
Binary files /dev/null and b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_model.jpg differ
diff --git a/docs/modules/Model_predictive_speed_and_steering_control.rst b/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst
similarity index 92%
rename from docs/modules/Model_predictive_speed_and_steering_control.rst
rename to docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst
index fdb6573d08..76a6819a46 100644
--- a/docs/modules/Model_predictive_speed_and_steering_control.rst
+++ b/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst
@@ -5,23 +5,22 @@ Model predictive speed and steering control
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/model_predictive_speed_and_steer_control/animation.gif?raw=true
:alt: Model predictive speed and steering control
- Model predictive speed and steering control
-
-code:
-
-`PythonRobotics/model_predictive_speed_and_steer_control.py at master ·
-AtsushiSakai/PythonRobotics `__
-
This is a path tracking simulation using model predictive control (MPC).
The MPC controller controls vehicle speed and steering base on
-linealized model.
+linearized model.
This code uses cvxpy as an optimization modeling tool.
- `Welcome to CVXPY 1.0 — CVXPY 1.0.6
documentation `__
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.model_predictive_speed_and_steer_control.model_predictive_speed_and_steer_control.iterative_linear_mpc_control
+
+
MPC modeling
~~~~~~~~~~~~
@@ -133,5 +132,5 @@ Reference
- `Vehicle Dynamics and Control \| Rajesh Rajamani \|
Springer `__
-- `MPC Course Material - MPC Lab @
- UC-Berkeley `__
+- `MPC Book - MPC Lab @
+ UC-Berkeley `__
diff --git a/docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst b/docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst
new file mode 100644
index 0000000000..19bb0e4c14
--- /dev/null
+++ b/docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst
@@ -0,0 +1,165 @@
+Move to a Pose Control
+----------------------
+
+In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/move_to_pose/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.move_to_pose.move_to_pose.move_to_pose
+
+
+Position Control of non-Holonomic Systems
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+This section explains the logic of a position controller for systems with constraint (non-Holonomic system).
+
+The position control of a 1-DOF (Degree of Freedom) system is quite straightforward. We only need to compute a position error and multiply it with a proportional gain to create a command. The actuator of the system takes this command and drive the system to the target position. This controller can be easily extended to higher dimensions (e.g., using Kp_x and Kp_y gains for a 2D position control). In these systems, the number of control commands is equal to the number of degrees of freedom (Holonomic system).
+
+To describe the configuration of a car on a 2D plane, we need three DOFs (i.e., x, y, and theta). But to drive a car we only need two control commands (theta_engine and theta_steering_wheel). This difference is because of a constraint between the x and y DOFs. The relationship between the delta_x and delta_y is governed by the theta_steering_wheel.
+
+Note that a car is normally a non-Holonomic system but if the road is slippery, the car turns into a Holonomic system and thus it needs three independent commands to be controlled.
+
+PathFinderController class
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Constructor
+^^^^^^^^^^^
+
+.. code-block:: ipython3
+
+ PathFinderController(Kp_rho, Kp_alpha, Kp_beta)
+
+Constructs an instantiate of the PathFinderController for navigating a 3-DOF wheeled robot on a 2D plane.
+
+Parameters:
+
+- | **Kp_rho** : The linear velocity gain to translate the robot along a line towards the goal
+- | **Kp_alpha** : The angular velocity gain to rotate the robot towards the goal
+- | **Kp_beta** : The offset angular velocity gain accounting for smooth merging to the goal angle (i.e., it helps the robot heading to be parallel to the target angle.)
+
+
+Member function(s)
+^^^^^^^^^^^^^^^^^^
+
+.. code-block:: ipython3
+
+ calc_control_command(x_diff, y_diff, theta, theta_goal)
+
+Returns the control command for the linear and angular velocities as well as the distance to goal
+
+Parameters:
+
+- | **x_diff** : The position of target with respect to current robot position in x direction
+- | **y_diff** : The position of target with respect to current robot position in y direction
+- | **theta** : The current heading angle of robot with respect to x axis
+- | **theta_goal** : The target angle of robot with respect to x axis
+
+Returns:
+
+- | **rho** : The distance between the robot and the goal position
+- | **v** : Command linear velocity
+- | **w** : Command angular velocity
+
+How does the Algorithm Work
+~~~~~~~~~~~~~~~~~~~~~~~~~~~
+The distance between the robot and the goal position, :math:`\rho`, is computed as
+
+.. math::
+ \rho = \sqrt{(x_{robot} - x_{target})^2 + (y_{robot} - y_{target})^2}.
+
+The distance :math:`\rho` is used to determine the robot speed. The idea is to slow down the robot as it gets closer to the target.
+
+.. math::
+ v = K_P{_\rho} \times \rho\qquad
+ :label: move_to_a_pose_eq1
+
+Note that for your applications, you need to tune the speed gain, :math:`K_P{_\rho}` to a proper value.
+
+To turn the robot and align its heading, :math:`\theta`, toward the target position (not orientation), :math:`\rho \vec{u}`, we need to compute the angle difference :math:`\alpha`.
+
+.. math::
+ \alpha = (\arctan2(y_{diff}, x_{diff}) - \theta + \pi) mod (2\pi) - \pi
+
+The term :math:`mod(2\pi)` is used to map the angle to :math:`[-\pi, \pi)` range.
+
+Lastly to correct the orientation of the robot, we need to compute the orientation error, :math:`\beta`, of the robot.
+
+.. math::
+ \beta = (\theta_{goal} - \theta - \alpha + \pi) mod (2\pi) - \pi
+
+Note that to cancel out the effect of :math:`\alpha` when the robot is at the vicinity of the target, the term
+
+:math:`-\alpha` is included.
+
+The final angular speed command is given by
+
+.. math::
+ \omega = K_P{_\alpha} \alpha - K_P{_\beta} \beta\qquad
+ :label: move_to_a_pose_eq2
+
+The linear and angular speeds (Equations :eq:`move_to_a_pose_eq1` and :eq:`move_to_a_pose_eq2`) are the output of the algorithm.
+
+Move to a Pose Robot (Class)
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+This program (move_to_pose_robot.py) provides a Robot class to define different robots with different specifications.
+Using this class, you can simulate different robots simultaneously and compare the effect of your parameter settings.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/move_to_pos_robot_class/animation.gif
+
+Note: The robot class is based on PathFinderController class in 'the move_to_pose.py'.
+
+Robot Class
+^^^^^^^^^^^^
+
+Constructor
+^^^^^^^^^^^^
+
+.. code-block:: ipython3
+
+ Robot(name, color, max_linear_speed, max_angular_speed, path_finder_controller)
+
+Constructs an instantiate of the 3-DOF wheeled Robot navigating on a 2D plane
+
+Parameters:
+
+- | **name** : (string) The name of the robot
+- | **color** : (string) The color of the robot
+- | **max_linear_speed** : (float) The maximum linear speed that the robot can go
+- | **max_angular_speed** : (float) The maximum angular speed that the robot can rotate about its vertical axis
+- | **path_finder_controller** : (PathFinderController) A configurable controller to finds the path and calculates command linear and angular velocities.
+
+Member function(s)
+^^^^^^^^^^^^^^^^^^^
+
+.. code-block:: ipython3
+
+ set_start_target_poses(pose_start, pose_target)
+
+Sets the start and target positions of the robot.
+
+Parameters:
+
+- | **pose_start** : (Pose) Start postion of the robot (see the Pose class)
+- | **pose_target** : (Pose) Target postion of the robot (see the Pose class)
+
+.. code-block:: ipython3
+
+ move(dt)
+
+Move the robot for one time step increment
+
+Parameters:
+
+- | **dt** : time increment
+
+
+
+References
+~~~~~~~~~~~~
+- PathFinderController class
+- `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink
+ p102 `__
diff --git a/docs/modules/6_path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst
new file mode 100644
index 0000000000..742cc807e6
--- /dev/null
+++ b/docs/modules/6_path_tracking/path_tracking_main.rst
@@ -0,0 +1,19 @@
+.. _`Path Tracking`:
+
+Path Tracking
+=============
+
+Path tracking is the ability of a robot to follow the reference path generated by a path planner while simultaneously stabilizing the robot. The path tracking controller may need to account for modeling error and other forms of uncertainty. In path tracking, feedback control techniques and optimization based control techniques are widely used[22]. Fig.6 shows simulations using rear wheel feedback steering control and PID speed control, and iterative linear model predictive path tracking control[27].
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ pure_pursuit_tracking/pure_pursuit_tracking
+ stanley_control/stanley_control
+ rear_wheel_feedback_control/rear_wheel_feedback_control
+ lqr_steering_control/lqr_steering_control
+ lqr_speed_and_steering_control/lqr_speed_and_steering_control
+ model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control
+ cgmres_nmpc/cgmres_nmpc
+ move_to_a_pose/move_to_a_pose
diff --git a/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst
new file mode 100644
index 0000000000..ff6749bbbe
--- /dev/null
+++ b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst
@@ -0,0 +1,22 @@
+Pure pursuit tracking
+---------------------
+
+Path tracking simulation with pure pursuit steering control and PID
+speed control.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/pure_pursuit/animation.gif
+
+The red line is a target course, the green cross means the target point
+for pure pursuit control, the blue line is the tracking.
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.pure_pursuit.pure_pursuit.pure_pursuit_steer_control
+
+
+Reference
+~~~~~~~~~~~
+
+- `A Survey of Motion Planning and Control Techniques for Self-driving
+ Urban Vehicles `_
diff --git a/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst
new file mode 100644
index 0000000000..56d0db63ad
--- /dev/null
+++ b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst
@@ -0,0 +1,18 @@
+Rear wheel feedback control
+---------------------------
+
+Path tracking simulation with rear wheel feedback steering control and
+PID speed control.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.rear_wheel_feedback_control.rear_wheel_feedback_control.rear_wheel_feedback_control
+
+
+Reference
+~~~~~~~~~~~
+- `A Survey of Motion Planning and Control Techniques for Self-driving
+ Urban Vehicles `__
diff --git a/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst
new file mode 100644
index 0000000000..3c491804f6
--- /dev/null
+++ b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst
@@ -0,0 +1,22 @@
+Stanley control
+---------------
+
+Path tracking simulation with Stanley steering control and PID speed
+control.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: PathTracking.stanley_control.stanley_control.stanley_control
+
+
+Reference
+~~~~~~~~~~~
+
+- `Stanley: The robot that won the DARPA grand
+ challenge `_
+
+- `Automatic Steering Methods for Autonomous Automobile Path
+ Tracking `_
diff --git a/docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png
similarity index 100%
rename from docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png
rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png
diff --git a/docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png
similarity index 100%
rename from docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png
rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png
diff --git a/docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png
similarity index 100%
rename from docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png
rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png
diff --git a/docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png
similarity index 100%
rename from docs/modules/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png
rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png
diff --git a/docs/modules/7_arm_navigation/arm_navigation_main.rst b/docs/modules/7_arm_navigation/arm_navigation_main.rst
new file mode 100644
index 0000000000..7acd3ee7d3
--- /dev/null
+++ b/docs/modules/7_arm_navigation/arm_navigation_main.rst
@@ -0,0 +1,12 @@
+.. _`Arm Navigation`:
+
+Arm Navigation
+==============
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ planar_two_link_ik
+ n_joint_arm_to_point_control
+ obstacle_avoidance_arm_navigation
diff --git a/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst b/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst
new file mode 100644
index 0000000000..56900acde1
--- /dev/null
+++ b/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst
@@ -0,0 +1,20 @@
+N joint arm to point control
+----------------------------
+
+N joint arm to a point control simulation.
+
+This is a interactive simulation.
+
+You can set the goal position of the end effector with left-click on the
+plotting area.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif
+
+In this simulation N = 10, however, you can change it.
+
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: ArmNavigation.n_joint_arm_to_point_control.n_joint_arm_to_point_control.main
+
diff --git a/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst b/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst
new file mode 100644
index 0000000000..4433ab531b
--- /dev/null
+++ b/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst
@@ -0,0 +1,11 @@
+Arm navigation with obstacle avoidance
+--------------------------------------
+
+Arm navigation with obstacle avoidance simulation.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: ArmNavigation.arm_obstacle_navigation.arm_obstacle_navigation.main
diff --git a/docs/modules/Planar_Two_Link_IK.rst b/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst
similarity index 98%
rename from docs/modules/Planar_Two_Link_IK.rst
rename to docs/modules/7_arm_navigation/planar_two_link_ik_main.rst
index c5643ced6d..5b2712eb48 100644
--- a/docs/modules/Planar_Two_Link_IK.rst
+++ b/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst
@@ -5,14 +5,17 @@ Two joint arm to point control
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/two_joint_arm_to_point_control/animation.gif
:alt: TwoJointArmToPointControl
- TwoJointArmToPointControl
-
This is two joint arm to a point control simulation.
This is a interactive simulation.
-You can set the goal position of the end effector with left-click on the
-ploting area.
+You can set the goal position of the end effector with left-click on the plotting area.
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: ArmNavigation.two_joint_arm_to_point_control.two_joint_arm_to_point_control.main
+
Inverse Kinematics for a Planar Two-Link Robotic Arm
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
diff --git a/docs/modules/8_aerial_navigation/aerial_navigation_main.rst b/docs/modules/8_aerial_navigation/aerial_navigation_main.rst
new file mode 100644
index 0000000000..7f76689770
--- /dev/null
+++ b/docs/modules/8_aerial_navigation/aerial_navigation_main.rst
@@ -0,0 +1,12 @@
+.. _`Aerial Navigation`:
+
+Aerial Navigation
+=================
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ drone_3d_trajectory_following/drone_3d_trajectory_following
+ rocket_powered_landing/rocket_powered_landing
+
diff --git a/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst b/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst
new file mode 100644
index 0000000000..1805bb3f6d
--- /dev/null
+++ b/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst
@@ -0,0 +1,11 @@
+Drone 3d trajectory following
+-----------------------------
+
+This is a 3d trajectory following simulation for a quadrotor.
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: AerialNavigation.drone_3d_trajectory_following.drone_3d_trajectory_following.quad_sim
diff --git a/docs/modules/rocket_powered_landing.rst b/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst
similarity index 95%
rename from docs/modules/rocket_powered_landing.rst
rename to docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst
index da7546e8f0..4bf5117500 100644
--- a/docs/modules/rocket_powered_landing.rst
+++ b/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst
@@ -1,3 +1,13 @@
+Rocket powered landing
+-----------------------------
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: AerialNavigation.rocket_powered_landing.rocket_powered_landing.main
+
Simulation
~~~~~~~~~~
@@ -32,8 +42,6 @@ Simulation
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif
:alt: gif
- gif
-
Equation generation
~~~~~~~~~~~~~~~~~~~
@@ -145,8 +153,8 @@ Equation generation
-Ref
-~~~
+References
+~~~~~~~~~~
- Python implementation of ‘Successive Convexification for 6-DoF Mars
Rocket Powered Landing with Free-Final-Time’ paper by Michael Szmuk
diff --git a/docs/modules/9_bipedal/bipedal_main.rst b/docs/modules/9_bipedal/bipedal_main.rst
new file mode 100644
index 0000000000..dc387dc4e8
--- /dev/null
+++ b/docs/modules/9_bipedal/bipedal_main.rst
@@ -0,0 +1,11 @@
+.. _`Bipedal`:
+
+Bipedal
+=================
+
+.. toctree::
+ :maxdepth: 2
+ :caption: Contents
+
+ bipedal_planner/bipedal_planner
+
diff --git a/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst b/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst
new file mode 100644
index 0000000000..6253715cc1
--- /dev/null
+++ b/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst
@@ -0,0 +1,11 @@
+Bipedal Planner
+-----------------------------
+
+Bipedal Walking with modifying designated footsteps
+
+.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Bipedal/bipedal_planner/animation.gif
+
+Code Link
+~~~~~~~~~~~~~~~
+
+.. autofunction:: Bipedal.bipedal_planner.bipedal_planner.BipedalPlanner
diff --git a/docs/modules/aerial_navigation.rst b/docs/modules/aerial_navigation.rst
deleted file mode 100644
index e6a8881616..0000000000
--- a/docs/modules/aerial_navigation.rst
+++ /dev/null
@@ -1,18 +0,0 @@
-.. _aerial_navigation:
-
-Aerial Navigation
-=================
-
-Drone 3d trajectory following
------------------------------
-
-This is a 3d trajectory following simulation for a quadrotor.
-
-|3|
-
-rocket powered landing
------------------------------
-
-.. include:: rocket_powered_landing.rst
-
-.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif
diff --git a/docs/modules/appendix.rst b/docs/modules/appendix.rst
deleted file mode 100644
index 8840603bca..0000000000
--- a/docs/modules/appendix.rst
+++ /dev/null
@@ -1,9 +0,0 @@
-.. _appendix:
-
-Appendix
-==============
-
-.. include:: Kalmanfilter_basics.rst
-
-.. include:: Kalmanfilter_basics_2.rst
-
diff --git a/docs/modules/arm_navigation.rst b/docs/modules/arm_navigation.rst
deleted file mode 100644
index 81dea01b0e..0000000000
--- a/docs/modules/arm_navigation.rst
+++ /dev/null
@@ -1,31 +0,0 @@
-.. _arm_navigation:
-
-Arm Navigation
-==============
-
-.. include:: Planar_Two_Link_IK.rst
-
-
-N joint arm to point control
-----------------------------
-
-N joint arm to a point control simulation.
-
-This is a interactive simulation.
-
-You can set the goal position of the end effector with left-click on the
-ploting area.
-
-|n_joints_arm|
-
-In this simulation N = 10, however, you can change it.
-
-Arm navigation with obstacle avoidance
---------------------------------------
-
-Arm navigation with obstacle avoidance simulation.
-
-|obstacle|
-
-.. |n_joints_arm| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif
-.. |obstacle| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif
diff --git a/docs/modules/extended_kalman_filter_localization.rst b/docs/modules/extended_kalman_filter_localization.rst
deleted file mode 100644
index 565fb4ed20..0000000000
--- a/docs/modules/extended_kalman_filter_localization.rst
+++ /dev/null
@@ -1,154 +0,0 @@
-
-Extended Kalman Filter Localization
------------------------------------
-
-.. code-block:: ipython3
-
- from IPython.display import Image
- Image(filename="ekf.png",width=600)
-
-
-
-
-.. image:: extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png
- :width: 600px
-
-
-
-.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif
- :alt: EKF
-
- EKF
-
-This is a sensor fusion localization with Extended Kalman Filter(EKF).
-
-The blue line is true trajectory, the black line is dead reckoning
-trajectory,
-
-the green point is positioning observation (ex. GPS), and the red line
-is estimated trajectory with EKF.
-
-The red ellipse is estimated covariance ellipse with EKF.
-
-Code: `PythonRobotics/extended_kalman_filter.py at master ·
-AtsushiSakai/PythonRobotics `__
-
-Filter design
-~~~~~~~~~~~~~
-
-In this simulation, the robot has a state vector includes 4 states at
-time :math:`t`.
-
-.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t]
-
-x, y are a 2D x-y position, :math:`\phi` is orientation, and v is
-velocity.
-
-In the code, “xEst” means the state vector.
-`code `__
-
-And, :math:`P_t` is covariace matrix of the state,
-
-:math:`Q` is covariance matrix of process noise,
-
-:math:`R` is covariance matrix of observation noise at time :math:`t`
-
-
-
-The robot has a speed sensor and a gyro sensor.
-
-So, the input vecor can be used as each time step
-
-.. math:: \textbf{u}_t=[v_t, \omega_t]
-
-Also, the robot has a GNSS sensor, it means that the robot can observe
-x-y position at each time.
-
-.. math:: \textbf{z}_t=[x_t,y_t]
-
-The input and observation vector includes sensor noise.
-
-In the code, “observation” function generates the input and observation
-vector with noise
-`code `__
-
-Motion Model
-~~~~~~~~~~~~
-
-The robot model is
-
-.. math:: \dot{x} = vcos(\phi)
-
-.. math:: \dot{y} = vsin((\phi)
-
-.. math:: \dot{\phi} = \omega
-
-So, the motion model is
-
-.. math:: \textbf{x}_{t+1} = F\textbf{x}_t+B\textbf{u}_t
-
-where
-
-:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
-
-:math:`\begin{equation*} B= \begin{bmatrix} cos(\phi)dt & 0\\ sin(\phi)dt & 0\\ 0 & dt\\ 1 & 0\\ \end{bmatrix} \end{equation*}`
-
-:math:`dt` is a time interval.
-
-This is implemented at
-`code `__
-
-Its Jacobian matrix is
-
-:math:`\begin{equation*} J_F= \begin{bmatrix} \frac{dx}{dx}& \frac{dx}{dy} & \frac{dx}{d\phi} & \frac{dx}{dv}\\ \frac{dy}{dx}& \frac{dy}{dy} & \frac{dy}{d\phi} & \frac{dy}{dv}\\ \frac{d\phi}{dx}& \frac{d\phi}{dy} & \frac{d\phi}{d\phi} & \frac{d\phi}{dv}\\ \frac{dv}{dx}& \frac{dv}{dy} & \frac{dv}{d\phi} & \frac{dv}{dv}\\ \end{bmatrix} \end{equation*}`
-
-:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & -v sin(\phi)dt & cos(\phi)dt\\ 0 & 1 & v cos(\phi)dt & sin(\phi) dt\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1\\ \end{bmatrix} \end{equation*}`
-
-Observation Model
-~~~~~~~~~~~~~~~~~
-
-The robot can get x-y position infomation from GPS.
-
-So GPS Observation model is
-
-.. math:: \textbf{z}_{t} = H\textbf{x}_t
-
-where
-
-:math:`\begin{equation*} B= \begin{bmatrix} 1 & 0 & 0& 0\\ 0 & 1 & 0& 0\\ \end{bmatrix} \end{equation*}`
-
-Its Jacobian matrix is
-
-:math:`\begin{equation*} J_H= \begin{bmatrix} \frac{dx}{dx}& \frac{dx}{dy} & \frac{dx}{d\phi} & \frac{dx}{dv}\\ \frac{dy}{dx}& \frac{dy}{dy} & \frac{dy}{d\phi} & \frac{dy}{dv}\\ \end{bmatrix} \end{equation*}`
-
-:math:`\begin{equation*} = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}`
-
-Extented Kalman Filter
-~~~~~~~~~~~~~~~~~~~~~~
-
-Localization process using Extendted Kalman Filter:EKF is
-
-=== Predict ===
-
-:math:`x_{Pred} = Fx_t+Bu_t`
-
-:math:`P_{Pred} = J_FP_t J_F^T + Q`
-
-=== Update ===
-
-:math:`z_{Pred} = Hx_{Pred}`
-
-:math:`y = z - z_{Pred}`
-
-:math:`S = J_H P_{Pred}.J_H^T + R`
-
-:math:`K = P_{Pred}.J_H^T S^{-1}`
-
-:math:`x_{t+1} = x_{Pred} + Ky`
-
-:math:`P_{t+1} = ( I - K J_H) P_{Pred}`
-
-Ref:
-~~~~
-
-- `PROBABILISTIC-ROBOTICS.ORG `__
diff --git a/docs/modules/introduction.rst b/docs/modules/introduction.rst
deleted file mode 100644
index e9fce33443..0000000000
--- a/docs/modules/introduction.rst
+++ /dev/null
@@ -1,6 +0,0 @@
-
-Introduction
-============
-
-Ref
----
diff --git a/docs/modules/localization.rst b/docs/modules/localization.rst
deleted file mode 100644
index ddbf056c82..0000000000
--- a/docs/modules/localization.rst
+++ /dev/null
@@ -1,71 +0,0 @@
-.. _localization:
-
-Localization
-============
-
-.. include:: extended_kalman_filter_localization.rst
-
-
-Unscented Kalman Filter localization
-------------------------------------
-
-|2|
-
-This is a sensor fusion localization with Unscented Kalman Filter(UKF).
-
-The lines and points are same meaning of the EKF simulation.
-
-Ref:
-
-- `Discriminatively Trained Unscented Kalman Filter for Mobile Robot
- Localization`_
-
-Particle filter localization
-----------------------------
-
-|3|
-
-This is a sensor fusion localization with Particle Filter(PF).
-
-The blue line is true trajectory, the black line is dead reckoning
-trajectory,
-
-and the red line is estimated trajectory with PF.
-
-It is assumed that the robot can measure a distance from landmarks
-(RFID).
-
-This measurements are used for PF localization.
-
-Ref:
-
-- `PROBABILISTIC ROBOTICS`_
-
-Histogram filter localization
------------------------------
-
-|4|
-
-This is a 2D localization example with Histogram filter.
-
-The red cross is true position, black points are RFID positions.
-
-The blue grid shows a position probability of histogram filter.
-
-In this simulation, x,y are unknown, yaw is known.
-
-The filter integrates speed input and range observations from RFID for
-localization.
-
-Initial position is not needed.
-
-Ref:
-
-- `PROBABILISTIC ROBOTICS`_
-
-.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/
-.. _Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization: https://www.researchgate.net/publication/267963417_Discriminatively_Trained_Unscented_Kalman_Filter_for_Mobile_Robot_Localization
-
-.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/unscented_kalman_filter/animation.gif
-.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/particle_filter/animation.gif
-.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/histogram_filter/animation.gif
diff --git a/docs/modules/mapping.rst b/docs/modules/mapping.rst
deleted file mode 100644
index 7f30abcead..0000000000
--- a/docs/modules/mapping.rst
+++ /dev/null
@@ -1,43 +0,0 @@
-.. _mapping:
-
-Mapping
-=======
-
-Gaussian grid map
------------------
-
-This is a 2D Gaussian grid mapping example.
-
-|2|
-
-Ray casting grid map
---------------------
-
-This is a 2D ray casting grid mapping example.
-
-|3|
-
-k-means object clustering
--------------------------
-
-This is a 2D object clustering with k-means algorithm.
-
-|4|
-
-Object shape recognition using circle fitting
----------------------------------------------
-
-This is an object shape recognition using circle fitting.
-
-|5|
-
-The blue circle is the true object shape.
-
-The red crosses are observations from a ranging sensor.
-
-The red circle is the estimated object shape using circle fitting.
-
-.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/gaussian_grid_map/animation.gif
-.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif
-.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/kmeans_clustering/animation.gif
-.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/circle_fitting/animation.gif
diff --git a/docs/modules/path_planning.rst b/docs/modules/path_planning.rst
deleted file mode 100644
index f74867dcdf..0000000000
--- a/docs/modules/path_planning.rst
+++ /dev/null
@@ -1,458 +0,0 @@
-.. _path_planning:
-
-Path Planning
-=============
-
-Dynamic Window Approach
------------------------
-
-This is a 2D navigation sample code with Dynamic Window Approach.
-
-- `The Dynamic Window Approach to Collision
- Avoidance `__
-
-|DWA|
-
-Grid based search
------------------
-
-Dijkstra algorithm
-~~~~~~~~~~~~~~~~~~
-
-This is a 2D grid based shortest path planning with Dijkstra's
-algorithm.
-
-|Dijkstra|
-
-In the animation, cyan points are searched nodes.
-
-.. _a*-algorithm:
-
-A\* algorithm
-~~~~~~~~~~~~~
-
-This is a 2D grid based shortest path planning with A star algorithm.
-
-|astar|
-
-In the animation, cyan points are searched nodes.
-
-Its heuristic is 2D Euclid distance.
-
-Potential Field algorithm
-~~~~~~~~~~~~~~~~~~~~~~~~~
-
-This is a 2D grid based path planning with Potential Field algorithm.
-
-|PotentialField|
-
-In the animation, the blue heat map shows potential value on each grid.
-
-Ref:
-
-- `Robotic Motion Planning:Potential
- Functions `__
-
-Model Predictive Trajectory Generator
--------------------------------------
-
-This is a path optimization sample on model predictive trajectory
-generator.
-
-This algorithm is used for state lattice planner.
-
-Path optimization sample
-~~~~~~~~~~~~~~~~~~~~~~~~
-
-|4|
-
-Lookup table generation sample
-~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-
-|5|
-
-Ref:
-
-- `Optimal rough terrain trajectory generation for wheeled mobile
- robots `__
-
-State Lattice Planning
-----------------------
-
-This script is a path planning code with state lattice planning.
-
-This code uses the model predictive trajectory generator to solve
-boundary problem.
-
-Ref:
-
-- `Optimal rough terrain trajectory generation for wheeled mobile
- robots `__
-
-- `State Space Sampling of Feasible Motions for High-Performance Mobile
- Robot Navigation in Complex
- Environments `__
-
-Uniform polar sampling
-~~~~~~~~~~~~~~~~~~~~~~
-
-|6|
-
-Biased polar sampling
-~~~~~~~~~~~~~~~~~~~~~
-
-|7|
-
-Lane sampling
-~~~~~~~~~~~~~
-
-|8|
-
-.. _probabilistic-road-map-(prm)-planning:
-
-Probabilistic Road-Map (PRM) planning
--------------------------------------
-
-|PRM|
-
-This PRM planner uses Dijkstra method for graph search.
-
-In the animation, blue points are sampled points,
-
-Cyan crosses means searched points with Dijkstra method,
-
-The red line is the final path of PRM.
-
-Ref:
-
-- `Probabilistic roadmap -
- Wikipedia `__
-
-
-
-Voronoi Road-Map planning
--------------------------
-
-|VRM|
-
-This Voronoi road-map planner uses Dijkstra method for graph search.
-
-In the animation, blue points are Voronoi points,
-
-Cyan crosses mean searched points with Dijkstra method,
-
-The red line is the final path of Vornoi Road-Map.
-
-Ref:
-
-- `Robotic Motion
- Planning `__
-
-.. _rapidly-exploring-random-trees-(rrt):
-
-Rapidly-Exploring Random Trees (RRT)
-------------------------------------
-
-Basic RRT
-~~~~~~~~~
-
-|9|
-
-This is a simple path planning code with Rapidly-Exploring Random Trees
-(RRT)
-
-Black circles are obstacles, green line is a searched tree, red crosses
-are start and goal positions.
-
-.. _rrt*:
-
-RRT\*
-~~~~~
-
-|10|
-
-This is a path planning code with RRT\*
-
-Black circles are obstacles, green line is a searched tree, red crosses
-are start and goal positions.
-
-.. include:: rrt_star.rst
-
-Ref:
-
-- `Incremental Sampling-based Algorithms for Optimal Motion
- Planning `__
-
-- `Sampling-based Algorithms for Optimal Motion
- Planning `__
-
-RRT with dubins path
-~~~~~~~~~~~~~~~~~~~~
-
-|PythonRobotics|
-
-Path planning for a car robot with RRT and dubins path planner.
-
-.. _rrt*-with-dubins-path:
-
-RRT\* with dubins path
-~~~~~~~~~~~~~~~~~~~~~~
-
-|AtsushiSakai/PythonRobotics|
-
-Path planning for a car robot with RRT\* and dubins path planner.
-
-.. _rrt*-with-reeds-sheep-path:
-
-RRT\* with reeds-sheep path
-~~~~~~~~~~~~~~~~~~~~~~~~~~~
-
-|11|
-
-Path planning for a car robot with RRT\* and reeds sheep path planner.
-
-.. _informed-rrt*:
-
-Informed RRT\*
-~~~~~~~~~~~~~~
-
-|irrt|
-
-This is a path planning code with Informed RRT*.
-
-The cyan ellipse is the heuristic sampling domain of Informed RRT*.
-
-Ref:
-
-- `Informed RRT\*: Optimal Sampling-based Path Planning Focused via
- Direct Sampling of an Admissible Ellipsoidal
- Heuristic `__
-
-.. _batch-informed-rrt*:
-
-Batch Informed RRT\*
-~~~~~~~~~~~~~~~~~~~~
-
-|irrt2|
-
-This is a path planning code with Batch Informed RRT*.
-
-Ref:
-
-- `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the
- Heuristically Guided Search of Implicit Random Geometric
- Graphs `__
-
-.. _closed-loop-rrt*:
-
-Closed Loop RRT\*
-~~~~~~~~~~~~~~~~~
-
-A vehicle model based path planning with closed loop RRT*.
-
-|CLRRT|
-
-In this code, pure-pursuit algorithm is used for steering control,
-
-PID is used for speed control.
-
-Ref:
-
-- `Motion Planning in Complex Environments using Closed-loop
- Prediction `__
-
-- `Real-time Motion Planning with Applications to Autonomous Urban
- Driving `__
-
-- `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning
- Using Closed-loop Prediction `__
-
-.. _lqr-rrt*:
-
-LQR-RRT\*
-~~~~~~~~~
-
-This is a path planning simulation with LQR-RRT*.
-
-A double integrator motion model is used for LQR local planner.
-
-|LQRRRT|
-
-Ref:
-
-- `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically
- Derived Extension
- Heuristics `__
-
-- `MahanFathi/LQR-RRTstar: LQR-RRT\* method is used for random motion
- planning of a simple pendulum in its phase
- plot `__
-
-Cubic spline planning
----------------------
-
-A sample code for cubic path planning.
-
-This code generates a curvature continuous path based on x-y waypoints
-with cubic spline.
-
-Heading angle of each point can be also calculated analytically.
-
-|12|
-|13|
-|14|
-
-B-Spline planning
------------------
-
-|B-Spline|
-
-This is a path planning with B-Spline curse.
-
-If you input waypoints, it generates a smooth path with B-Spline curve.
-
-The final course should be on the first and last waypoints.
-
-Ref:
-
-- `B-spline - Wikipedia `__
-
-.. _eta^3-spline-path-planning:
-
-Eta^3 Spline path planning
---------------------------
-
-|eta3|
-
-This is a path planning with Eta^3 spline.
-
-Ref:
-
-- `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile
- Robots `__
-
-Bezier path planning
---------------------
-
-A sample code of Bezier path planning.
-
-It is based on 4 control points Beier path.
-
-|Bezier1|
-
-If you change the offset distance from start and end point,
-
-You can get different Beizer course:
-
-|Bezier2|
-
-Ref:
-
-- `Continuous Curvature Path Generation Based on Bezier Curves for
- Autonomous
- Vehicles `__
-
-Quintic polynomials planning
-----------------------------
-
-Motion planning with quintic polynomials.
-
-|2|
-
-It can calculate 2D path, velocity, and acceleration profile based on
-quintic polynomials.
-
-Ref:
-
-- `Local Path Planning And Motion Control For Agv In
- Positioning `__
-
-Dubins path planning
---------------------
-
-A sample code for Dubins path planning.
-
-|dubins|
-
-Ref:
-
-- `Dubins path -
- Wikipedia `__
-
-Reeds Shepp planning
---------------------
-
-A sample code with Reeds Shepp path planning.
-
-|RSPlanning|
-
-Ref:
-
-- `15.3.2 Reeds-Shepp
- Curves `__
-
-- `optimal paths for a car that goes both forwards and
- backwards `__
-
-- `ghliu/pyReedsShepp: Implementation of Reeds Shepp
- curve. `__
-
-LQR based path planning
------------------------
-
-A sample code using LQR based path planning for double integrator model.
-
-|RSPlanning2|
-
-Optimal Trajectory in a Frenet Frame
-------------------------------------
-
-|15|
-
-This is optimal trajectory generation in a Frenet Frame.
-
-The cyan line is the target course and black crosses are obstacles.
-
-The red line is predicted path.
-
-Ref:
-
-- `Optimal Trajectory Generation for Dynamic Street Scenarios in a
- Frenet
- Frame `__
-
-- `Optimal trajectory generation for dynamic street scenarios in a
- Frenet Frame `__
-
-.. |DWA| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif
-.. |Dijkstra| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif
-.. |astar| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif
-.. |PotentialField| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif
-.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif
-.. |5| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png?raw=True
-.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif
-.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif
-.. |8| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif
-.. |PRM| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif
-.. |VRM| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif
-.. |9| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif
-.. |10| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif
-.. |PythonRobotics| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif
-.. |AtsushiSakai/PythonRobotics| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif
-.. |11| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif
-.. |irrt| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif
-.. |irrt2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif
-.. |CLRRT| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif
-.. |LQRRRT| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif
-.. |12| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_1.png?raw=True
-.. |13| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_2.png?raw=True
-.. |14| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_3.png?raw=True
-.. |B-Spline| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/BSplinePath/Figure_1.png?raw=True
-.. |eta3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif
-.. |Bezier1| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/BezierPath/Figure_1.png?raw=True
-.. |Bezier2| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/BezierPath/Figure_2.png?raw=True
-.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/QuinticPolynomialsPlanner/animation.gif
-.. |dubins| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True
-.. |RSPlanning| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true
-.. |RSPlanning2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true
-.. |15| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif
diff --git a/docs/modules/path_tracking.rst b/docs/modules/path_tracking.rst
deleted file mode 100644
index 7788866ad3..0000000000
--- a/docs/modules/path_tracking.rst
+++ /dev/null
@@ -1,107 +0,0 @@
-.. _path_tracking:
-
-Path tracking
-=============
-
-move to a pose control
-----------------------
-
-This is a simulation of moving to a pose control
-
-|2|
-
-Ref:
-
-- `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink
- p102 `__
-
-Pure pursuit tracking
----------------------
-
-Path tracking simulation with pure pursuit steering control and PID
-speed control.
-
-|3|
-
-The red line is a target course, the green cross means the target point
-for pure pursuit control, the blue line is the tracking.
-
-Ref:
-
-- `A Survey of Motion Planning and Control Techniques for Self-driving
- Urban Vehicles `__
-
-Stanley control
----------------
-
-Path tracking simulation with Stanley steering control and PID speed
-control.
-
-|4|
-
-Ref:
-
-- `Stanley: The robot that won the DARPA grand
- challenge `__
-
-- `Automatic Steering Methods for Autonomous Automobile Path
- Tracking `__
-
-Rear wheel feedback control
----------------------------
-
-Path tracking simulation with rear wheel feedback steering control and
-PID speed control.
-
-|5|
-
-Ref:
-
-- `A Survey of Motion Planning and Control Techniques for Self-driving
- Urban Vehicles `__
-
-.. _linearquadratic-regulator-(lqr)-steering-control:
-
-Linear–quadratic regulator (LQR) steering control
--------------------------------------------------
-
-Path tracking simulation with LQR steering control and PID speed
-control.
-
-|6|
-
-Ref:
-
-- `ApolloAuto/apollo: An open autonomous driving
- platform `__
-
-.. _linearquadratic-regulator-(lqr)-speed-and-steering-control:
-
-Linear–quadratic regulator (LQR) speed and steering control
------------------------------------------------------------
-
-Path tracking simulation with LQR speed and steering control.
-
-|7|
-
-Ref:
-
-- `Towards fully autonomous driving: Systems and algorithms - IEEE
- Conference
- Publication `__
-
-.. include:: Model_predictive_speed_and_steering_control.rst
-
-Ref:
-
-- `notebook `__
-
-
-.. include:: cgmres_nmpc.rst
-
-.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif
-.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/pure_pursuit/animation.gif
-.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif
-.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif
-.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif
-.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif
diff --git a/docs/modules/rrt_star.rst b/docs/modules/rrt_star.rst
deleted file mode 100644
index 5b8d62e7e1..0000000000
--- a/docs/modules/rrt_star.rst
+++ /dev/null
@@ -1,27 +0,0 @@
-
-Simulation
-^^^^^^^^^^
-
-.. code-block:: ipython3
-
- from IPython.display import Image
- Image(filename="Figure_1.png",width=600)
-
-
-
-
-.. image:: rrt_star_files/rrt_star_1_0.png
- :width: 600px
-
-
-
-.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif
- :alt: gif
-
- gif
-
-Ref
-^^^
-
-- `Sampling-based Algorithms for Optimal Motion
- Planning `__
diff --git a/docs/modules/slam.rst b/docs/modules/slam.rst
deleted file mode 100644
index 981c45ada5..0000000000
--- a/docs/modules/slam.rst
+++ /dev/null
@@ -1,93 +0,0 @@
-.. _slam:
-
-SLAM
-====
-
-Simultaneous Localization and Mapping(SLAM) examples
-
-.. _iterative-closest-point-(icp)-matching:
-
-Iterative Closest Point (ICP) Matching
---------------------------------------
-
-This is a 2D ICP matching example with singular value decomposition.
-
-It can calculate a rotation matrix and a translation vector between
-points to points.
-
-|3|
-
-Ref:
-
-- `Introduction to Mobile Robotics: Iterative Closest Point Algorithm`_
-
-EKF SLAM
---------
-
-This is an Extended Kalman Filter based SLAM example.
-
-The blue line is ground truth, the black line is dead reckoning, the red
-line is the estimated trajectory with EKF SLAM.
-
-The green crosses are estimated landmarks.
-
-|4|
-
-Ref:
-
-- `PROBABILISTIC ROBOTICS`_
-
-.. include:: FastSLAM1.rst
-
-|5|
-
-Ref:
-
-- `PROBABILISTIC ROBOTICS`_
-
-- `SLAM simulations by Tim Bailey`_
-
-FastSLAM 2.0
-------------
-
-This is a feature based SLAM example using FastSLAM 2.0.
-
-The animation has the same meanings as one of FastSLAM 1.0.
-
-|6|
-
-Ref:
-
-- `PROBABILISTIC ROBOTICS`_
-
-- `SLAM simulations by Tim Bailey`_
-
-Graph based SLAM
-----------------
-
-This is a graph based SLAM example.
-
-The blue line is ground truth.
-
-The black line is dead reckoning.
-
-The red line is the estimated trajectory with Graph based SLAM.
-
-The black stars are landmarks for graph edge generation.
-
-|7|
-
-Ref:
-
-- `A Tutorial on Graph-Based SLAM`_
-
-.. _`Introduction to Mobile Robotics: Iterative Closest Point Algorithm`: https://cs.gmu.edu/~kosecka/cs685/cs685-icp.pdf
-.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/
-.. _SLAM simulations by Tim Bailey: http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm
-.. _A Tutorial on Graph-Based SLAM: http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf
-
-.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif
-.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif
-.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif
-.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif
-.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif
diff --git a/docs/notebook_template.ipynb b/docs/notebook_template.ipynb
deleted file mode 100644
index 40943b09a2..0000000000
--- a/docs/notebook_template.ipynb
+++ /dev/null
@@ -1,96 +0,0 @@
-{
- "cells": [
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "## Title"
- ]
- },
- {
- "cell_type": "code",
- "execution_count": 1,
- "metadata": {},
- "outputs": [
- {
- "ename": "FileNotFoundError",
- "evalue": "[Errno 2] No such file or directory: 'hoge.png'",
- "output_type": "error",
- "traceback": [
- "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
- "\u001b[0;31mFileNotFoundError\u001b[0m Traceback (most recent call last)",
- "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m()\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[0;32mfrom\u001b[0m \u001b[0mIPython\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdisplay\u001b[0m \u001b[0;32mimport\u001b[0m \u001b[0mImage\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 2\u001b[0;31m \u001b[0mImage\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mfilename\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0;34m\"hoge.png\"\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mwidth\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0;36m600\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
- "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, data, url, filename, format, embed, width, height, retina, unconfined, metadata)\u001b[0m\n\u001b[1;32m 1149\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0munconfined\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0munconfined\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1150\u001b[0m super(Image, self).__init__(data=data, url=url, filename=filename, \n\u001b[0;32m-> 1151\u001b[0;31m metadata=metadata)\n\u001b[0m\u001b[1;32m 1152\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1153\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwidth\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mNone\u001b[0m \u001b[0;32mand\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmetadata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mget\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'width'\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m{\u001b[0m\u001b[0;34m}\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
- "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, data, url, filename, metadata)\u001b[0m\n\u001b[1;32m 607\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmetadata\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m{\u001b[0m\u001b[0;34m}\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 608\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 609\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreload\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 610\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_check_data\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 611\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
- "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36mreload\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 1180\u001b[0m \u001b[0;34m\"\"\"Reload the raw data from file or URL.\"\"\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1181\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0membed\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m-> 1182\u001b[0;31m \u001b[0msuper\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mImage\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreload\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 1183\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mretina\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1184\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_retina_shape\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
- "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36mreload\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 632\u001b[0m \u001b[0;34m\"\"\"Reload the raw data from file or URL.\"\"\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 633\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfilename\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0;32mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 634\u001b[0;31m \u001b[0;32mwith\u001b[0m \u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfilename\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_read_flags\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 635\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdata\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mread\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 636\u001b[0m \u001b[0;32melif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0murl\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0;32mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
- "\u001b[0;31mFileNotFoundError\u001b[0m: [Errno 2] No such file or directory: 'hoge.png'"
- ]
- }
- ],
- "source": [
- "from IPython.display import Image\n",
- "Image(filename=\"hoge.png\",width=600)"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "\n"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Section1"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Section2\n",
- "\n",
- "$\\begin{equation*}\n",
- "F=\n",
- "\\begin{bmatrix}\n",
- "1 & 0 & 0 & 0\\\\\n",
- "0 & 1 & 0 & 0\\\\\n",
- "0 & 0 & 1 & 0 \\\\\n",
- "0 & 0 & 0 & 0 \\\\\n",
- "\\end{bmatrix}\n",
- "\\end{equation*}$"
- ]
- },
- {
- "cell_type": "markdown",
- "metadata": {},
- "source": [
- "### Ref"
- ]
- }
- ],
- "metadata": {
- "kernelspec": {
- "display_name": "Python 3",
- "language": "python",
- "name": "python3"
- },
- "language_info": {
- "codemirror_mode": {
- "name": "ipython",
- "version": 3
- },
- "file_extension": ".py",
- "mimetype": "text/x-python",
- "name": "python",
- "nbconvert_exporter": "python",
- "pygments_lexer": "ipython3",
- "version": "3.6.6"
- }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/environment.yml b/environment.yml
deleted file mode 100644
index 34d7edeec6..0000000000
--- a/environment.yml
+++ /dev/null
@@ -1,9 +0,0 @@
-name: python_robotics
-dependencies:
-- python==3.6
-- matplotlib
-- scipy
-- numpy==1.15
-- pandas
-- pip:
- - cvxpy
diff --git a/mypy.ini b/mypy.ini
new file mode 100644
index 0000000000..1215375ed9
--- /dev/null
+++ b/mypy.ini
@@ -0,0 +1,2 @@
+[mypy]
+ignore_missing_imports = True
\ No newline at end of file
diff --git a/requirements.txt b/requirements.txt
deleted file mode 100644
index 1398664be8..0000000000
--- a/requirements.txt
+++ /dev/null
@@ -1,5 +0,0 @@
-numpy
-pandas
-scipy
-matplotlib
-cvxpy
diff --git a/requirements/environment.yml b/requirements/environment.yml
new file mode 100644
index 0000000000..023a3d75bf
--- /dev/null
+++ b/requirements/environment.yml
@@ -0,0 +1,10 @@
+name: python_robotics
+channels:
+ - conda-forge
+dependencies:
+ - python=3.13
+ - pip
+ - scipy
+ - numpy
+ - cvxpy
+ - matplotlib
diff --git a/requirements/requirements.txt b/requirements/requirements.txt
new file mode 100644
index 0000000000..050bd1e57c
--- /dev/null
+++ b/requirements/requirements.txt
@@ -0,0 +1,9 @@
+numpy == 2.2.4
+scipy == 1.15.2
+matplotlib == 3.10.1
+cvxpy == 1.7.3
+ecos == 2.0.14
+pytest == 8.4.2 # For unit test
+pytest-xdist == 3.8.0 # For unit test
+mypy == 1.18.2 # For unit test
+ruff == 0.13.2 # For unit test
diff --git a/ruff.toml b/ruff.toml
new file mode 100644
index 0000000000..d76b715a06
--- /dev/null
+++ b/ruff.toml
@@ -0,0 +1,18 @@
+line-length = 88
+
+select = ["F", "E", "W", "UP"]
+ignore = ["E501", "E741", "E402"]
+exclude = [
+]
+
+# Assume Python 3.13
+target-version = "py313"
+
+[per-file-ignores]
+
+[mccabe]
+# Unlike Flake8, default to a complexity level of 10.
+max-complexity = 10
+
+[pydocstyle]
+convention = "numpy"
diff --git a/runtests.sh b/runtests.sh
index fbb87df518..c4460c8aa7 100755
--- a/runtests.sh
+++ b/runtests.sh
@@ -1,4 +1,9 @@
+#!/usr/bin/env bash
+cd "$(dirname "$0")" || exit 1
echo "Run test suites! "
-#python -m unittest discover tests
-#python -Wignore -m unittest discover tests #ignore warning
-coverage run -m unittest discover tests # generate coverage file
+
+# === pytest based test runner ===
+# -Werror: warning as error
+# --durations=0: show ranking of test durations
+# -l (--showlocals); show local variables when test failed
+pytest tests -l -Werror --durations=0
diff --git a/tests/__init__.py b/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/tests/conftest.py b/tests/conftest.py
new file mode 100644
index 0000000000..b707b22d00
--- /dev/null
+++ b/tests/conftest.py
@@ -0,0 +1,13 @@
+"""Path hack to make tests work."""
+import sys
+import os
+import pytest
+
+TEST_DIR = os.path.dirname(os.path.abspath(__file__))
+sys.path.append(TEST_DIR) # to import this file from test code.
+ROOT_DIR = os.path.dirname(TEST_DIR)
+sys.path.append(ROOT_DIR)
+
+
+def run_this_test(file):
+ pytest.main(args=["-W", "error", "-Werror", "--pythonwarnings=error", os.path.abspath(file)])
diff --git a/tests/test_LQR_planner.py b/tests/test_LQR_planner.py
index 5ece27f80b..be12195eac 100644
--- a/tests/test_LQR_planner.py
+++ b/tests/test_LQR_planner.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathPlanning.LQRPlanner import lqr_planner as m
-import sys
-sys.path.append("./PathPlanning/LQRPlanner")
-from PathPlanning.LQRPlanner import LQRplanner as m
+def test_1():
+ m.SHOW_ANIMATION = False
+ m.main()
-print(__file__)
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_a_star.py b/tests/test_a_star.py
index 61276e6a31..82f76401ad 100644
--- a/tests/test_a_star.py
+++ b/tests/test_a_star.py
@@ -1,20 +1,11 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(__file__) + "/../")
-try:
- from PathPlanning.AStar import a_star as m
-except:
- raise
+import conftest
+from PathPlanning.AStar import a_star as m
-class Test(TestCase):
+def test_1():
+ m.show_animation = False
+ m.main()
- def test1(self):
- m.show_animation = False
- m.main()
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_a_star_searching_two_side.py b/tests/test_a_star_searching_two_side.py
new file mode 100644
index 0000000000..ad90ebc509
--- /dev/null
+++ b/tests/test_a_star_searching_two_side.py
@@ -0,0 +1,16 @@
+import conftest
+from PathPlanning.AStar import a_star_searching_from_two_side as m
+
+
+def test1():
+ m.show_animation = False
+ m.main(800)
+
+
+def test2():
+ m.show_animation = False
+ m.main(5000) # increase obstacle number, block path
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_a_star_variants.py b/tests/test_a_star_variants.py
new file mode 100644
index 0000000000..b9ef791402
--- /dev/null
+++ b/tests/test_a_star_variants.py
@@ -0,0 +1,44 @@
+import PathPlanning.AStar.a_star_variants as a_star
+import conftest
+
+
+def test_1():
+ # A* with beam search
+ a_star.show_animation = False
+
+ a_star.use_beam_search = True
+ a_star.main()
+ reset_all()
+
+ # A* with iterative deepening
+ a_star.use_iterative_deepening = True
+ a_star.main()
+ reset_all()
+
+ # A* with dynamic weighting
+ a_star.use_dynamic_weighting = True
+ a_star.main()
+ reset_all()
+
+ # theta*
+ a_star.use_theta_star = True
+ a_star.main()
+ reset_all()
+
+ # A* with jump point
+ a_star.use_jump_point = True
+ a_star.main()
+ reset_all()
+
+
+def reset_all():
+ a_star.show_animation = False
+ a_star.use_beam_search = False
+ a_star.use_iterative_deepening = False
+ a_star.use_dynamic_weighting = False
+ a_star.use_theta_star = False
+ a_star.use_jump_point = False
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_batch_informed_rrt_star.py b/tests/test_batch_informed_rrt_star.py
index e83684d92c..cf0a9827a8 100644
--- a/tests/test_batch_informed_rrt_star.py
+++ b/tests/test_batch_informed_rrt_star.py
@@ -1,22 +1,14 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(__file__) + "/../")
-try:
- from PathPlanning.BatchInformedRRTStar import batch_informed_rrtstar as m
-except:
- raise
+import random
-print(__file__)
+import conftest
+from PathPlanning.BatchInformedRRTStar import batch_informed_rrt_star as m
-class Test(TestCase):
+def test_1():
+ m.show_animation = False
+ random.seed(12345)
+ m.main(maxIter=10)
- def test1(self):
- m.show_animation = False
- m.main(maxIter=10)
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_behavior_tree.py b/tests/test_behavior_tree.py
new file mode 100644
index 0000000000..0898690448
--- /dev/null
+++ b/tests/test_behavior_tree.py
@@ -0,0 +1,207 @@
+import pytest
+import conftest
+
+from MissionPlanning.BehaviorTree.behavior_tree import (
+ BehaviorTreeFactory,
+ Status,
+ ActionNode,
+)
+
+
+def test_sequence_node1():
+ xml_string = """
+
+
+
+
+
+
+
+ """
+ bt_factory = BehaviorTreeFactory()
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick()
+ assert bt.root.status == Status.RUNNING
+ assert bt.root.children[0].status == Status.SUCCESS
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+ bt.tick()
+ bt.tick()
+ assert bt.root.status == Status.FAILURE
+ assert bt.root.children[0].status is None
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+
+
+def test_sequence_node2():
+ xml_string = """
+
+
+
+
+
+
+
+ """
+ bt_factory = BehaviorTreeFactory()
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick_while_running()
+ assert bt.root.status == Status.SUCCESS
+ assert bt.root.children[0].status is None
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+
+
+def test_selector_node1():
+ xml_string = """
+
+
+
+
+
+
+
+ """
+ bt_factory = BehaviorTreeFactory()
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick()
+ assert bt.root.status == Status.RUNNING
+ assert bt.root.children[0].status == Status.FAILURE
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+ bt.tick()
+ assert bt.root.status == Status.SUCCESS
+ assert bt.root.children[0].status is None
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+
+
+def test_selector_node2():
+ xml_string = """
+
+
+
+
+
+
+
+
+ """
+ bt_factory = BehaviorTreeFactory()
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick_while_running()
+ assert bt.root.status == Status.FAILURE
+ assert bt.root.children[0].status is None
+ assert bt.root.children[1].status is None
+
+
+def test_while_do_else_node():
+ xml_string = """
+
+
+
+
+
+ """
+
+ class CountNode(ActionNode):
+ def __init__(self, name, count_threshold):
+ super().__init__(name)
+ self.count = 0
+ self.count_threshold = count_threshold
+
+ def tick(self):
+ self.count += 1
+ if self.count >= self.count_threshold:
+ return Status.FAILURE
+ else:
+ return Status.SUCCESS
+
+ bt_factory = BehaviorTreeFactory()
+ bt_factory.register_node_builder(
+ "Count",
+ lambda node: CountNode(
+ node.attrib.get("name", CountNode.__name__),
+ int(node.attrib["count_threshold"]),
+ ),
+ )
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick()
+ assert bt.root.status == Status.RUNNING
+ assert bt.root.children[0].status == Status.SUCCESS
+ assert bt.root.children[1].status is Status.SUCCESS
+ assert bt.root.children[2].status is None
+ bt.tick()
+ assert bt.root.status == Status.RUNNING
+ assert bt.root.children[0].status == Status.SUCCESS
+ assert bt.root.children[1].status is Status.SUCCESS
+ assert bt.root.children[2].status is None
+ bt.tick()
+ assert bt.root.status == Status.SUCCESS
+ assert bt.root.children[0].status is None
+ assert bt.root.children[1].status is None
+ assert bt.root.children[2].status is None
+
+
+def test_node_children():
+ # ControlNode Must have children
+ xml_string = """
+
+
+ """
+ bt_factory = BehaviorTreeFactory()
+ with pytest.raises(ValueError):
+ bt_factory.build_tree(xml_string)
+
+ # DecoratorNode Must have child
+ xml_string = """
+
+
+ """
+ with pytest.raises(ValueError):
+ bt_factory.build_tree(xml_string)
+
+ # DecoratorNode Must have only one child
+ xml_string = """
+
+
+
+
+ """
+ with pytest.raises(ValueError):
+ bt_factory.build_tree(xml_string)
+
+ # ActionNode Must have no children
+ xml_string = """
+
+
+
+ """
+ with pytest.raises(ValueError):
+ bt_factory.build_tree(xml_string)
+
+ # WhileDoElse Must have exactly 2 or 3 children
+ xml_string = """
+
+
+
+ """
+ with pytest.raises(ValueError):
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick()
+
+ xml_string = """
+
+
+
+
+
+
+ """
+ with pytest.raises(ValueError):
+ bt = bt_factory.build_tree(xml_string)
+ bt.tick()
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_bezier_path.py b/tests/test_bezier_path.py
index 94ec8f5c31..67a5d520de 100644
--- a/tests/test_bezier_path.py
+++ b/tests/test_bezier_path.py
@@ -1,16 +1,16 @@
-from unittest import TestCase
+import conftest
+from PathPlanning.BezierPath import bezier_path as m
-import sys
-sys.path.append("./PathPlanning/BezierPath/")
-from PathPlanning.BezierPath import bezier_path as m
+def test_1():
+ m.show_animation = False
+ m.main()
-print(__file__)
+def test_2():
+ m.show_animation = False
+ m.main2()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
- m.main2()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_bipedal_planner.py b/tests/test_bipedal_planner.py
new file mode 100644
index 0000000000..818957bcdc
--- /dev/null
+++ b/tests/test_bipedal_planner.py
@@ -0,0 +1,18 @@
+import conftest
+from Bipedal.bipedal_planner import bipedal_planner as m
+
+
+def test_1():
+ bipedal_planner = m.BipedalPlanner()
+
+ footsteps = [[0.0, 0.2, 0.0],
+ [0.3, 0.2, 0.0],
+ [0.3, 0.2, 0.2],
+ [0.3, 0.2, 0.2],
+ [0.0, 0.2, 0.2]]
+ bipedal_planner.set_ref_footsteps(footsteps)
+ bipedal_planner.walk(plot=False)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_breadth_first_search.py b/tests/test_breadth_first_search.py
new file mode 100644
index 0000000000..bfc63e39d6
--- /dev/null
+++ b/tests/test_breadth_first_search.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.BreadthFirstSearch import breadth_first_search as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_bspline_path.py b/tests/test_bspline_path.py
new file mode 100644
index 0000000000..4918c9810f
--- /dev/null
+++ b/tests/test_bspline_path.py
@@ -0,0 +1,74 @@
+import conftest
+import numpy as np
+import pytest
+from PathPlanning.BSplinePath import bspline_path
+
+
+def test_list_input():
+ way_point_x = [-1.0, 3.0, 4.0, 2.0, 1.0]
+ way_point_y = [0.0, -3.0, 1.0, 1.0, 3.0]
+ n_course_point = 50 # sampling number
+
+ rax, ray, heading, curvature = bspline_path.approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5)
+
+ assert len(rax) == len(ray) == len(heading) == len(curvature)
+
+ rix, riy, heading, curvature = bspline_path.interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point)
+
+ assert len(rix) == len(riy) == len(heading) == len(curvature)
+
+
+def test_array_input():
+ way_point_x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0])
+ way_point_y = np.array([0.0, -3.0, 1.0, 1.0, 3.0])
+ n_course_point = 50 # sampling number
+
+ rax, ray, heading, curvature = bspline_path.approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5)
+
+ assert len(rax) == len(ray) == len(heading) == len(curvature)
+
+ rix, riy, heading, curvature = bspline_path.interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point)
+
+ assert len(rix) == len(riy) == len(heading) == len(curvature)
+
+
+def test_degree_change():
+ way_point_x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0])
+ way_point_y = np.array([0.0, -3.0, 1.0, 1.0, 3.0])
+ n_course_point = 50 # sampling number
+
+ rax, ray, heading, curvature = bspline_path.approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5, degree=4)
+
+ assert len(rax) == len(ray) == len(heading) == len(curvature)
+
+ rix, riy, heading, curvature = bspline_path.interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, degree=4)
+
+ assert len(rix) == len(riy) == len(heading) == len(curvature)
+
+ rax, ray, heading, curvature = bspline_path.approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5, degree=2)
+
+ assert len(rax) == len(ray) == len(heading) == len(curvature)
+
+ rix, riy, heading, curvature = bspline_path.interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, degree=2)
+
+ assert len(rix) == len(riy) == len(heading) == len(curvature)
+
+ with pytest.raises(ValueError):
+ bspline_path.approximate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, s=0.5, degree=1)
+
+ with pytest.raises(ValueError):
+ bspline_path.interpolate_b_spline_path(
+ way_point_x, way_point_y, n_course_point, degree=1)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_bug.py b/tests/test_bug.py
new file mode 100644
index 0000000000..f94794a45e
--- /dev/null
+++ b/tests/test_bug.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.BugPlanning import bug as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main(bug_0=True, bug_1=True, bug_2=True)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_catmull_rom_spline.py b/tests/test_catmull_rom_spline.py
new file mode 100644
index 0000000000..41a73588c3
--- /dev/null
+++ b/tests/test_catmull_rom_spline.py
@@ -0,0 +1,16 @@
+import conftest
+from PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path import catmull_rom_spline
+
+def test_catmull_rom_spline():
+ way_points = [[0, 0], [1, 2], [2, 0], [3, 3]]
+ num_points = 100
+
+ spline_x, spline_y = catmull_rom_spline(way_points, num_points)
+
+ assert spline_x.size > 0, "Spline X coordinates should not be empty"
+ assert spline_y.size > 0, "Spline Y coordinates should not be empty"
+
+ assert spline_x.shape == spline_y.shape, "Spline X and Y coordinates should have the same shape"
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_cgmres_nmpc.py b/tests/test_cgmres_nmpc.py
index 8420ca1a5a..db3ada5065 100644
--- a/tests/test_cgmres_nmpc.py
+++ b/tests/test_cgmres_nmpc.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
+import conftest
+from PathTracking.cgmres_nmpc import cgmres_nmpc as m
-import sys
-if 'cvxpy' in sys.modules: # pragma: no cover
- sys.path.append("./PathTracking/cgmres_nmpc/")
- from PathTracking.cgmres_nmpc import cgmres_nmpc as m
+def test1():
+ m.show_animation = False
+ m.main()
- print(__file__)
- class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_circle_fitting.py b/tests/test_circle_fitting.py
index d184548227..b3888d7cc3 100644
--- a/tests/test_circle_fitting.py
+++ b/tests/test_circle_fitting.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from Mapping.circle_fitting import circle_fitting as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_closed_loop_rrt_star_car.py b/tests/test_closed_loop_rrt_star_car.py
index f82d3f2561..c33e413e92 100644
--- a/tests/test_closed_loop_rrt_star_car.py
+++ b/tests/test_closed_loop_rrt_star_car.py
@@ -1,25 +1,13 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/ClosedLoopRRTStar/")
-try:
- from PathPlanning.ClosedLoopRRTStar import closed_loop_rrt_star_car as m
-except:
- raise
+import conftest
+from PathPlanning.ClosedLoopRRTStar import closed_loop_rrt_star_car as m
+import random
-print(__file__)
+def test_1():
+ random.seed(12345)
+ m.show_animation = False
+ m.main(gx=1.0, gy=0.0, gyaw=0.0, max_iter=5)
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main(gx=1.0, gy=0.0, gyaw=0.0, maxIter=5)
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_clothoidal_paths.py b/tests/test_clothoidal_paths.py
new file mode 100644
index 0000000000..0b038c0338
--- /dev/null
+++ b/tests/test_clothoidal_paths.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.ClothoidPath import clothoid_path_planner as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_codestyle.py b/tests/test_codestyle.py
new file mode 100644
index 0000000000..55e558c184
--- /dev/null
+++ b/tests/test_codestyle.py
@@ -0,0 +1,138 @@
+"""
+Diff code style checker with ruff
+
+This code come from:
+https://github.com/scipy/scipy/blob/main/tools/lint.py
+
+Scipy's licence: https://github.com/scipy/scipy/blob/main/LICENSE.txt
+Copyright (c) 2001-2002 Enthought, Inc. 2003-2022, SciPy Developers.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions
+are met:
+
+1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+2. Redistributions in binary form must reproduce the above
+ copyright notice, this list of conditions and the following
+ disclaimer in the documentation and/or other materials provided
+ with the distribution.
+
+3. Neither the name of the copyright holder nor the names of its
+ contributors may be used to endorse or promote products derived
+ from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+"""
+import conftest
+import os
+import subprocess
+
+
+CONFIG = os.path.join(
+ os.path.abspath(os.path.dirname(os.path.dirname(__file__))),
+ 'ruff.toml',
+)
+
+ROOT_DIR = os.path.abspath(os.path.dirname(os.path.dirname(__file__)))
+
+
+def run_ruff(files, fix):
+ if not files:
+ return 0, ""
+ args = ['--fix'] if fix else []
+ res = subprocess.run(
+ ['ruff', 'check', f'--config={CONFIG}'] + args + files,
+ stdout=subprocess.PIPE,
+ encoding='utf-8'
+ )
+ return res.returncode, res.stdout
+
+
+def rev_list(branch, num_commits):
+ """List commits in reverse chronological order.
+ Only the first `num_commits` are shown.
+ """
+ res = subprocess.run(
+ [
+ 'git',
+ 'rev-list',
+ '--max-count',
+ f'{num_commits}',
+ '--first-parent',
+ branch
+ ],
+ stdout=subprocess.PIPE,
+ encoding='utf-8',
+ )
+ res.check_returncode()
+ return res.stdout.rstrip('\n').split('\n')
+
+
+def find_branch_point(branch):
+ """Find when the current branch split off from the given branch.
+ It is based off of this Stackoverflow post:
+ https://stackoverflow.com/questions/1527234/finding-a-branch-point-with-git#4991675
+ """
+ branch_commits = rev_list('HEAD', 1000)
+ main_commits = set(rev_list(branch, 1000))
+ for branch_commit in branch_commits:
+ if branch_commit in main_commits:
+ return branch_commit
+
+ # If a branch split off over 1000 commits ago we will fail to find
+ # the ancestor.
+ raise RuntimeError(
+ 'Failed to find a common ancestor in the last 1000 commits')
+
+
+def find_diff(sha):
+ """Find the diff since the given sha."""
+ files = ['*.py']
+ res = subprocess.run(
+ ['git', 'diff', '--unified=0', sha, '--'] + files,
+ stdout=subprocess.PIPE,
+ encoding='utf-8'
+ )
+ res.check_returncode()
+ return res.stdout
+
+
+def diff_files(sha):
+ """Find the diff since the given SHA."""
+ res = subprocess.run(
+ ['git', 'diff', '--name-only', '--diff-filter=ACMR', '-z', sha, '--',
+ '*.py', '*.pyx', '*.pxd', '*.pxi'],
+ stdout=subprocess.PIPE,
+ encoding='utf-8'
+ )
+ res.check_returncode()
+ return [os.path.join(ROOT_DIR, f) for f in res.stdout.split('\0') if f]
+
+
+def test():
+ branch_commit = find_branch_point("origin/master")
+ files = diff_files(branch_commit)
+ print(files)
+ rc, errors = run_ruff(files, fix=True)
+ if errors:
+ print(errors)
+ else:
+ print("No lint errors found.")
+ assert rc == 0
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_cubature_kalman_filter.py b/tests/test_cubature_kalman_filter.py
new file mode 100644
index 0000000000..00f9d8bc5f
--- /dev/null
+++ b/tests/test_cubature_kalman_filter.py
@@ -0,0 +1,13 @@
+import conftest
+from Localization.cubature_kalman_filter import cubature_kalman_filter as m
+
+
+def test1():
+ m.show_final = False
+ m.show_animation = False
+ m.show_ellipse = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_d_star_lite.py b/tests/test_d_star_lite.py
new file mode 100644
index 0000000000..b60a140a89
--- /dev/null
+++ b/tests/test_d_star_lite.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.DStarLite import d_star_lite as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_depth_first_search.py b/tests/test_depth_first_search.py
new file mode 100644
index 0000000000..8dd009278f
--- /dev/null
+++ b/tests/test_depth_first_search.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.DepthFirstSearch import depth_first_search as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_dijkstra.py b/tests/test_dijkstra.py
index b86f2e6ce6..40404153d8 100644
--- a/tests/test_dijkstra.py
+++ b/tests/test_dijkstra.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from PathPlanning.Dijkstra import dijkstra as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_distance_map.py b/tests/test_distance_map.py
new file mode 100644
index 0000000000..df6e394e2c
--- /dev/null
+++ b/tests/test_distance_map.py
@@ -0,0 +1,118 @@
+import conftest # noqa
+import numpy as np
+from Mapping.DistanceMap import distance_map as m
+
+
+def test_compute_sdf():
+ """Test the computation of Signed Distance Field (SDF)"""
+ # Create a simple obstacle map for testing
+ obstacles = np.array([[0, 0, 0], [0, 1, 0], [0, 0, 0]])
+
+ sdf = m.compute_sdf(obstacles)
+
+ # Verify basic properties of SDF
+ assert sdf.shape == obstacles.shape, "SDF should have the same shape as input map"
+ assert np.all(np.isfinite(sdf)), "SDF should not contain infinite values"
+
+ # Verify SDF value is negative at obstacle position
+ assert sdf[1, 1] < 0, "SDF value should be negative at obstacle position"
+
+ # Verify SDF value is positive in free space
+ assert sdf[0, 0] > 0, "SDF value should be positive in free space"
+
+
+def test_compute_udf():
+ """Test the computation of Unsigned Distance Field (UDF)"""
+ # Create obstacle map for testing
+ obstacles = np.array([[0, 0, 0], [0, 1, 0], [0, 0, 0]])
+
+ udf = m.compute_udf(obstacles)
+
+ # Verify basic properties of UDF
+ assert udf.shape == obstacles.shape, "UDF should have the same shape as input map"
+ assert np.all(np.isfinite(udf)), "UDF should not contain infinite values"
+ assert np.all(udf >= 0), "All UDF values should be non-negative"
+
+ # Verify UDF value is 0 at obstacle position
+ assert np.abs(udf[1, 1]) < 1e-10, "UDF value should be 0 at obstacle position"
+
+ # Verify UDF value is 1 for adjacent cells
+ assert np.abs(udf[0, 1] - 1.0) < 1e-10, (
+ "UDF value should be 1 for cells adjacent to obstacle"
+ )
+ assert np.abs(udf[1, 0] - 1.0) < 1e-10, (
+ "UDF value should be 1 for cells adjacent to obstacle"
+ )
+ assert np.abs(udf[1, 2] - 1.0) < 1e-10, (
+ "UDF value should be 1 for cells adjacent to obstacle"
+ )
+ assert np.abs(udf[2, 1] - 1.0) < 1e-10, (
+ "UDF value should be 1 for cells adjacent to obstacle"
+ )
+
+
+def test_dt():
+ """Test the computation of 1D distance transform"""
+ # Create test data
+ d = np.array([m.INF, 0, m.INF])
+ m.dt(d)
+
+ # Verify distance transform results
+ assert np.all(np.isfinite(d)), (
+ "Distance transform result should not contain infinite values"
+ )
+ assert d[1] == 0, "Distance at obstacle position should be 0"
+ assert d[0] == 1, "Distance at adjacent position should be 1"
+ assert d[2] == 1, "Distance at adjacent position should be 1"
+
+
+def test_compute_sdf_empty():
+ """Test SDF computation with empty map"""
+ # Test with empty map (no obstacles)
+ empty_map = np.zeros((5, 5))
+ sdf = m.compute_sdf(empty_map)
+
+ assert np.all(sdf > 0), "All SDF values should be positive for empty map"
+ assert sdf.shape == empty_map.shape, "Output shape should match input shape"
+
+
+def test_compute_sdf_full():
+ """Test SDF computation with fully occupied map"""
+ # Test with fully occupied map
+ full_map = np.ones((5, 5))
+ sdf = m.compute_sdf(full_map)
+
+ assert np.all(sdf < 0), "All SDF values should be negative for fully occupied map"
+ assert sdf.shape == full_map.shape, "Output shape should match input shape"
+
+
+def test_compute_udf_invalid_input():
+ """Test UDF computation with invalid input values"""
+ # Test with invalid values (not 0 or 1)
+ invalid_map = np.array([[0, 2, 0], [0, -1, 0], [0, 0.5, 0]])
+
+ try:
+ m.compute_udf(invalid_map)
+ assert False, "Should raise ValueError for invalid input values"
+ except ValueError:
+ pass
+
+
+def test_compute_udf_empty():
+ """Test UDF computation with empty map"""
+ # Test with empty map
+ empty_map = np.zeros((5, 5))
+ udf = m.compute_udf(empty_map)
+
+ assert np.all(udf > 0), "All UDF values should be positive for empty map"
+ assert np.all(np.isfinite(udf)), "UDF should not contain infinite values"
+
+
+def test_main():
+ """Test the execution of main function"""
+ m.ENABLE_PLOT = False
+ m.main()
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_drone_3d_trajectory_following.py b/tests/test_drone_3d_trajectory_following.py
index 194a329946..e3fd417024 100644
--- a/tests/test_drone_3d_trajectory_following.py
+++ b/tests/test_drone_3d_trajectory_following.py
@@ -1,14 +1,12 @@
-from unittest import TestCase
+import conftest
+from AerialNavigation.drone_3d_trajectory_following \
+ import drone_3d_trajectory_following as m
-import sys
-sys.path.append("./AerialNavigation/drone_3d_trajectory_following/")
-from AerialNavigation.drone_3d_trajectory_following import drone_3d_trajectory_following as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_dstar.py b/tests/test_dstar.py
new file mode 100644
index 0000000000..f8f40fecef
--- /dev/null
+++ b/tests/test_dstar.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.DStar import dstar as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py
index d2ddb8cac1..aceb0b752a 100644
--- a/tests/test_dubins_path_planning.py
+++ b/tests/test_dubins_path_planning.py
@@ -1,32 +1,92 @@
-from unittest import TestCase
-from PathPlanning.DubinsPath import dubins_path_planning
import numpy as np
+import conftest
+from PathPlanning.DubinsPath import dubins_path_planner
-class Test(TestCase):
+np.random.seed(12345)
- def test1(self):
- start_x = 1.0 # [m]
- start_y = 1.0 # [m]
- start_yaw = np.deg2rad(45.0) # [rad]
- end_x = -3.0 # [m]
- end_y = -3.0 # [m]
- end_yaw = np.deg2rad(-45.0) # [rad]
+def check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x,
+ end_y, end_yaw):
+ assert (abs(px[0] - start_x) <= 0.01)
+ assert (abs(py[0] - start_y) <= 0.01)
+ assert (abs(pyaw[0] - start_yaw) <= 0.01)
+ assert (abs(px[-1] - end_x) <= 0.01)
+ assert (abs(py[-1] - end_y) <= 0.01)
+ assert (abs(pyaw[-1] - end_yaw) <= 0.01)
- curvature = 1.0
- px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning(
- start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature)
+def check_path_length(px, py, lengths):
+ path_len = sum(
+ [np.hypot(dx, dy) for (dx, dy) in zip(np.diff(px), np.diff(py))])
+ assert (abs(path_len - sum(lengths)) <= 0.1)
- assert(abs(px[-1] - end_x) <= 0.1)
- assert(abs(py[-1] - end_y) <= 0.1)
- assert(abs(pyaw[-1] - end_yaw) <= 0.1)
- def test2(self):
- dubins_path_planning.show_animation = False
- dubins_path_planning.main()
+def test_1():
+ start_x = 1.0 # [m]
+ start_y = 1.0 # [m]
+ start_yaw = np.deg2rad(45.0) # [rad]
- def test3(self):
- dubins_path_planning.show_animation = False
- dubins_path_planning.test()
+ end_x = -3.0 # [m]
+ end_y = -3.0 # [m]
+ end_yaw = np.deg2rad(-45.0) # [rad]
+
+ curvature = 1.0
+
+ px, py, pyaw, mode, lengths = dubins_path_planner.plan_dubins_path(
+ start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature)
+
+ check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x,
+ end_y, end_yaw)
+ check_path_length(px, py, lengths)
+
+
+def test_2():
+ dubins_path_planner.show_animation = False
+ dubins_path_planner.main()
+
+
+def test_3():
+ N_TEST = 10
+
+ for i in range(N_TEST):
+ start_x = (np.random.rand() - 0.5) * 10.0 # [m]
+ start_y = (np.random.rand() - 0.5) * 10.0 # [m]
+ start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+
+ end_x = (np.random.rand() - 0.5) * 10.0 # [m]
+ end_y = (np.random.rand() - 0.5) * 10.0 # [m]
+ end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+
+ curvature = 1.0 / (np.random.rand() * 5.0)
+
+ px, py, pyaw, mode, lengths = \
+ dubins_path_planner.plan_dubins_path(
+ start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature)
+
+ check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x,
+ end_y, end_yaw)
+ check_path_length(px, py, lengths)
+
+
+def test_path_plannings_types():
+ dubins_path_planner.show_animation = False
+ start_x = 1.0 # [m]
+ start_y = 1.0 # [m]
+ start_yaw = np.deg2rad(45.0) # [rad]
+
+ end_x = -3.0 # [m]
+ end_y = -3.0 # [m]
+ end_yaw = np.deg2rad(-45.0) # [rad]
+
+ curvature = 1.0
+
+ _, _, _, mode, _ = dubins_path_planner.plan_dubins_path(
+ start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature,
+ selected_types=["RSL"])
+
+ assert mode == ["R", "S", "L"]
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_dynamic_movement_primitives.py b/tests/test_dynamic_movement_primitives.py
new file mode 100644
index 0000000000..3ab1c8a32c
--- /dev/null
+++ b/tests/test_dynamic_movement_primitives.py
@@ -0,0 +1,49 @@
+import conftest
+import numpy as np
+from PathPlanning.DynamicMovementPrimitives import \
+ dynamic_movement_primitives
+
+
+def test_1():
+ # test that trajectory can be learned from user-passed data
+ T = 5
+ t = np.arange(0, T, 0.01)
+ sin_t = np.sin(t)
+ train_data = np.array([t, sin_t]).T
+
+ DMP_controller = dynamic_movement_primitives.DMP(train_data, T)
+ DMP_controller.recreate_trajectory(train_data[0], train_data[-1], 4)
+
+
+def test_2():
+ # test that length of trajectory is equal to desired number of timesteps
+ T = 5
+ t = np.arange(0, T, 0.01)
+ sin_t = np.sin(t)
+ train_data = np.array([t, sin_t]).T
+
+ DMP_controller = dynamic_movement_primitives.DMP(train_data, T)
+ t, path = DMP_controller.recreate_trajectory(train_data[0],
+ train_data[-1], 4)
+
+ assert(path.shape[0] == DMP_controller.timesteps)
+
+
+def test_3():
+ # check that learned trajectory is close to initial
+ T = 3*np.pi/2
+ A_noise = 0.02
+ t = np.arange(0, T, 0.01)
+ noisy_sin_t = np.sin(t) + A_noise*np.random.rand(len(t))
+ train_data = np.array([t, noisy_sin_t]).T
+
+ DMP_controller = dynamic_movement_primitives.DMP(train_data, T)
+ t, pos = DMP_controller.recreate_trajectory(train_data[0],
+ train_data[-1], T)
+
+ diff = abs(pos[:, 1] - noisy_sin_t)
+ assert(max(diff) < 5*A_noise)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_dynamic_window_approach.py b/tests/test_dynamic_window_approach.py
index ab2e0a27ac..fdb452b4a7 100644
--- a/tests/test_dynamic_window_approach.py
+++ b/tests/test_dynamic_window_approach.py
@@ -1,23 +1,48 @@
-from unittest import TestCase
+import conftest
+import numpy as np
-import sys
-import os
-sys.path.append(os.path.dirname(__file__) + "/../")
-try:
- from PathPlanning.DynamicWindowApproach import dynamic_window_approach as m
-except:
- raise
+from PathPlanning.DynamicWindowApproach import dynamic_window_approach as m
-print(__file__)
+def test_main1():
+ m.show_animation = False
+ m.main(gx=1.0, gy=1.0)
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main(gx=1.0, gy=1.0)
+def test_main2():
+ m.show_animation = False
+ m.main(gx=1.0, gy=1.0, robot_type=m.RobotType.rectangle)
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+def test_stuck_main():
+ m.show_animation = False
+ # adjust cost
+ m.config.to_goal_cost_gain = 0.2
+ m.config.obstacle_cost_gain = 2.0
+ # obstacles and goals for stuck condition
+ m.config.ob = -1 * np.array([[-1.0, -1.0],
+ [0.0, 2.0],
+ [2.0, 6.0],
+ [2.0, 8.0],
+ [3.0, 9.27],
+ [3.79, 9.39],
+ [7.25, 8.97],
+ [7.0, 2.0],
+ [3.0, 4.0],
+ [6.0, 5.0],
+ [3.5, 5.8],
+ [6.0, 9.0],
+ [8.8, 9.0],
+ [5.0, 9.0],
+ [7.5, 3.0],
+ [9.0, 8.0],
+ [5.8, 4.4],
+ [12.0, 12.0],
+ [3.0, 2.0],
+ [13.0, 13.0]
+ ])
+ m.main(gx=-5.0, gy=-7.0)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_ekf_slam.py b/tests/test_ekf_slam.py
index e651e0079c..4181bb64ba 100644
--- a/tests/test_ekf_slam.py
+++ b/tests/test_ekf_slam.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from SLAM.EKFSLAM import ekf_slam as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_elastic_bands.py b/tests/test_elastic_bands.py
new file mode 100644
index 0000000000..ad4e13af1a
--- /dev/null
+++ b/tests/test_elastic_bands.py
@@ -0,0 +1,23 @@
+import conftest
+import numpy as np
+from PathPlanning.ElasticBands.elastic_bands import ElasticBands
+
+
+def test_1():
+ path = np.load("PathPlanning/ElasticBands/path.npy")
+ obstacles_points = np.load("PathPlanning/ElasticBands/obstacles.npy")
+ obstacles = np.zeros((500, 500))
+ for x, y in obstacles_points:
+ size = 30 # Side length of the square
+ half_size = size // 2
+ x_start = max(0, x - half_size)
+ x_end = min(obstacles.shape[0], x + half_size)
+ y_start = max(0, y - half_size)
+ y_end = min(obstacles.shape[1], y + half_size)
+ obstacles[x_start:x_end, y_start:y_end] = 1
+ elastic_bands = ElasticBands(path, obstacles)
+ elastic_bands.update_bubbles()
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_eta3_spline_path.py b/tests/test_eta3_spline_path.py
index 33a4223d31..7fa3883ea5 100644
--- a/tests/test_eta3_spline_path.py
+++ b/tests/test_eta3_spline_path.py
@@ -1,10 +1,11 @@
-
-from unittest import TestCase
+import conftest
from PathPlanning.Eta3SplinePath import eta3_spline_path as m
-class Test(TestCase):
+def test_1():
+ m.show_animation = False
+ m.main()
+
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_extended_kalman_filter.py b/tests/test_extended_kalman_filter.py
index 299ee71b0a..d9ad6437a8 100644
--- a/tests/test_extended_kalman_filter.py
+++ b/tests/test_extended_kalman_filter.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from Localization.extended_kalman_filter import extended_kalman_filter as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_fast_slam1.py b/tests/test_fast_slam1.py
index 4b15e65c2d..b72ab6b9ef 100644
--- a/tests/test_fast_slam1.py
+++ b/tests/test_fast_slam1.py
@@ -1,24 +1,12 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from SLAM.FastSLAM1 import fast_slam1 as m
-except:
- raise
+import conftest
+from SLAM.FastSLAM1 import fast_slam1 as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.SIM_TIME = 3.0
+ m.main()
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.SIM_TIME = 3.0
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_fast_slam2.py b/tests/test_fast_slam2.py
index 4c1c967a41..95cdc69d42 100644
--- a/tests/test_fast_slam2.py
+++ b/tests/test_fast_slam2.py
@@ -1,24 +1,12 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from SLAM.FastSLAM2 import fast_slam2 as m
-except:
- raise
+import conftest
+from SLAM.FastSLAM2 import fast_slam2 as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.SIM_TIME = 3.0
+ m.main()
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.SIM_TIME = 3.0
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_flow_field.py b/tests/test_flow_field.py
new file mode 100644
index 0000000000..d049731fe5
--- /dev/null
+++ b/tests/test_flow_field.py
@@ -0,0 +1,11 @@
+import conftest
+import PathPlanning.FlowField.flowfield as flow_field
+
+
+def test():
+ flow_field.show_animation = False
+ flow_field.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_frenet_optimal_trajectory.py b/tests/test_frenet_optimal_trajectory.py
index 7a0ba5179e..b8761ff4a6 100644
--- a/tests/test_frenet_optimal_trajectory.py
+++ b/tests/test_frenet_optimal_trajectory.py
@@ -1,26 +1,48 @@
-from unittest import TestCase
+import conftest
+from PathPlanning.FrenetOptimalTrajectory import frenet_optimal_trajectory as m
+from PathPlanning.FrenetOptimalTrajectory.frenet_optimal_trajectory import (
+ LateralMovement,
+ LongitudinalMovement,
+)
-import sys
-import os
-sys.path.append("./PathPlanning/FrenetOptimalTrajectory/")
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from PathPlanning.FrenetOptimalTrajectory import frenet_optimal_trajectory as m
-except:
- raise
+def default_scenario_test():
+ m.show_animation = False
+ m.SIM_LOOP = 5
+ m.main()
-print(__file__)
+def high_speed_and_merging_and_stopping_scenario_test():
+ m.show_animation = False
+ m.LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED
+ m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.MERGING_AND_STOPPING
+ m.SIM_LOOP = 5
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.SIM_LOOP = 5
- m.main()
+def high_speed_and_velocity_keeping_scenario_test():
+ m.show_animation = False
+ m.LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED
+ m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING
+ m.SIM_LOOP = 5
+ m.main()
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+def low_speed_and_velocity_keeping_scenario_test():
+ m.show_animation = False
+ m.LATERAL_MOVEMENT = LateralMovement.LOW_SPEED
+ m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING
+ m.SIM_LOOP = 5
+ m.main()
+
+
+def low_speed_and_merging_and_stopping_scenario_test():
+ m.show_animation = False
+ m.LATERAL_MOVEMENT = LateralMovement.LOW_SPEED
+ m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.MERGING_AND_STOPPING
+ m.SIM_LOOP = 5
+ m.main()
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_gaussian_grid_map.py b/tests/test_gaussian_grid_map.py
index d6a6cf53b5..af1e138721 100644
--- a/tests/test_gaussian_grid_map.py
+++ b/tests/test_gaussian_grid_map.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from Mapping.gaussian_grid_map import gaussian_grid_map as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_graph_based_slam.py b/tests/test_graph_based_slam.py
index 89a6e14dfd..67d75f0f85 100644
--- a/tests/test_graph_based_slam.py
+++ b/tests/test_graph_based_slam.py
@@ -1,24 +1,12 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from SLAM.GraphBasedSLAM import graph_based_slam as m
-except:
- raise
+import conftest
+from SLAM.GraphBasedSLAM import graph_based_slam as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.SIM_TIME = 20.0
+ m.main()
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.SIM_TIME = 20.0
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_greedy_best_first_search.py b/tests/test_greedy_best_first_search.py
new file mode 100644
index 0000000000..e573ecf625
--- /dev/null
+++ b/tests/test_greedy_best_first_search.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.GreedyBestFirstSearch import greedy_best_first_search as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_grid_based_sweep_coverage_path_planner.py b/tests/test_grid_based_sweep_coverage_path_planner.py
new file mode 100644
index 0000000000..8cbe36eb49
--- /dev/null
+++ b/tests/test_grid_based_sweep_coverage_path_planner.py
@@ -0,0 +1,118 @@
+import conftest
+from PathPlanning.GridBasedSweepCPP \
+ import grid_based_sweep_coverage_path_planner
+
+grid_based_sweep_coverage_path_planner.do_animation = False
+RIGHT = grid_based_sweep_coverage_path_planner. \
+ SweepSearcher.MovingDirection.RIGHT
+LEFT = grid_based_sweep_coverage_path_planner. \
+ SweepSearcher.MovingDirection.LEFT
+UP = grid_based_sweep_coverage_path_planner. \
+ SweepSearcher.SweepDirection.UP
+DOWN = grid_based_sweep_coverage_path_planner. \
+ SweepSearcher.SweepDirection.DOWN
+
+
+def test_planning1():
+ ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0]
+ oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0]
+ resolution = 5.0
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=LEFT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=UP,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=UP,
+ )
+ assert len(px) >= 5
+
+
+def test_planning2():
+ ox = [0.0, 50.0, 50.0, 0.0, 0.0]
+ oy = [0.0, 0.0, 30.0, 30.0, 0.0]
+ resolution = 1.3
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=LEFT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=UP,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+
+def test_planning3():
+ ox = [0.0, 20.0, 50.0, 200.0, 130.0, 40.0, 0.0]
+ oy = [0.0, -80.0, 0.0, 30.0, 60.0, 80.0, 0.0]
+ resolution = 5.1
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=LEFT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=UP,
+ )
+ assert len(px) >= 5
+
+ px, py = grid_based_sweep_coverage_path_planner.planning(
+ ox, oy, resolution,
+ moving_direction=RIGHT,
+ sweeping_direction=DOWN,
+ )
+ assert len(px) >= 5
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_grid_map_lib.py b/tests/test_grid_map_lib.py
new file mode 100644
index 0000000000..670b357ad3
--- /dev/null
+++ b/tests/test_grid_map_lib.py
@@ -0,0 +1,40 @@
+from Mapping.grid_map_lib.grid_map_lib import GridMap
+import conftest
+import numpy as np
+
+
+def test_position_set():
+ grid_map = GridMap(100, 120, 0.5, 10.0, -0.5)
+
+ grid_map.set_value_from_xy_pos(10.1, -1.1, 1.0)
+ grid_map.set_value_from_xy_pos(10.1, -0.1, 1.0)
+ grid_map.set_value_from_xy_pos(10.1, 1.1, 1.0)
+ grid_map.set_value_from_xy_pos(11.1, 0.1, 1.0)
+ grid_map.set_value_from_xy_pos(10.1, 0.1, 1.0)
+ grid_map.set_value_from_xy_pos(9.1, 0.1, 1.0)
+
+
+def test_polygon_set():
+ ox = [0.0, 4.35, 20.0, 50.0, 100.0, 130.0, 40.0]
+ oy = [0.0, -4.15, -20.0, 0.0, 30.0, 60.0, 80.0]
+
+ grid_map = GridMap(600, 290, 0.7, 60.0, 30.5)
+
+ grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False)
+ grid_map.set_value_from_polygon(np.array(ox), np.array(oy),
+ 1.0, inside=False)
+
+
+def test_xy_and_grid_index_conversion():
+ grid_map = GridMap(100, 120, 0.5, 10.0, -0.5)
+
+ for x_ind in range(grid_map.width):
+ for y_ind in range(grid_map.height):
+ grid_ind = grid_map.calc_grid_index_from_xy_index(x_ind, y_ind)
+ x_ind_2, y_ind_2 = grid_map.calc_xy_index_from_grid_index(grid_ind)
+ assert x_ind == x_ind_2
+ assert y_ind == y_ind_2
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_histogram_filter.py b/tests/test_histogram_filter.py
index 6d7df824e0..4474ead097 100644
--- a/tests/test_histogram_filter.py
+++ b/tests/test_histogram_filter.py
@@ -1,25 +1,12 @@
-from unittest import TestCase
+import conftest
+from Localization.histogram_filter import histogram_filter as m
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from Localization.histogram_filter import histogram_filter as m
-except:
- raise
-
-print(__file__)
-
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.SIM_TIME = 1.0
- m.main()
+def test1():
+ m.show_animation = False
+ m.SIM_TIME = 1.0
+ m.main()
if __name__ == '__main__':
- test = Test()
- test.test1()
+ conftest.run_this_test(__file__)
diff --git a/tests/test_hybrid_a_star.py b/tests/test_hybrid_a_star.py
new file mode 100644
index 0000000000..dbcf3ba9f4
--- /dev/null
+++ b/tests/test_hybrid_a_star.py
@@ -0,0 +1,11 @@
+import conftest
+from PathPlanning.HybridAStar import hybrid_a_star as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_informed_rrt_star.py b/tests/test_informed_rrt_star.py
index a19f2465f2..10974ecfcb 100644
--- a/tests/test_informed_rrt_star.py
+++ b/tests/test_informed_rrt_star.py
@@ -1,24 +1,11 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../PathPlanning/InformedRRTStar/")
-try:
- from PathPlanning.InformedRRTStar import informed_rrt_star as m
-except:
- raise
+import conftest
+from PathPlanning.InformedRRTStar import informed_rrt_star as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_inverted_pendulum_lqr_control.py b/tests/test_inverted_pendulum_lqr_control.py
new file mode 100644
index 0000000000..62afda71c3
--- /dev/null
+++ b/tests/test_inverted_pendulum_lqr_control.py
@@ -0,0 +1,11 @@
+import conftest
+from InvertedPendulum import inverted_pendulum_lqr_control as m
+
+
+def test_1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_inverted_pendulum_mpc_control.py b/tests/test_inverted_pendulum_mpc_control.py
new file mode 100644
index 0000000000..94859c2e0a
--- /dev/null
+++ b/tests/test_inverted_pendulum_mpc_control.py
@@ -0,0 +1,12 @@
+import conftest
+
+from InvertedPendulum import inverted_pendulum_mpc_control as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_iterative_closest_point.py b/tests/test_iterative_closest_point.py
index 9c71688ec7..cdfa89cc55 100644
--- a/tests/test_iterative_closest_point.py
+++ b/tests/test_iterative_closest_point.py
@@ -1,12 +1,16 @@
-from unittest import TestCase
+import conftest
+from SLAM.ICPMatching import icp_matching as m
-from SLAM.iterative_closest_point import iterative_closest_point as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
+def test_2():
+ m.show_animation = False
+ m.main_3d_points()
- def test1(self):
- m.show_animation = False
- m.main()
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_kmeans_clustering.py b/tests/test_kmeans_clustering.py
index b5b2cb7a60..5e39d64ae6 100644
--- a/tests/test_kmeans_clustering.py
+++ b/tests/test_kmeans_clustering.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest
from Mapping.kmeans_clustering import kmeans_clustering as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_lqr_rrt_star.py b/tests/test_lqr_rrt_star.py
index a9c2f5eece..444b4616b8 100644
--- a/tests/test_lqr_rrt_star.py
+++ b/tests/test_lqr_rrt_star.py
@@ -1,24 +1,14 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../PathPlanning/LQRRRTStar/")
-try:
- from PathPlanning.LQRRRTStar import lqr_rrt_star as m
-except:
- raise
+import conftest # Add root path to sys.path
+from PathPlanning.LQRRRTStar import lqr_rrt_star as m
+import random
-print(__file__)
+random.seed(12345)
-class Test(TestCase):
+def test1():
+ m.show_animation = False
+ m.main(maxIter=5)
- def test1(self):
- m.show_animation = False
- m.main(maxIter=5)
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_lqr_speed_steer_control.py b/tests/test_lqr_speed_steer_control.py
index fb1a14af54..cee9759a26 100644
--- a/tests/test_lqr_speed_steer_control.py
+++ b/tests/test_lqr_speed_steer_control.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
-
-import sys
-sys.path.append("./PathTracking/lqr_speed_steer_control/")
-
+import conftest # Add root path to sys.path
from PathTracking.lqr_speed_steer_control import lqr_speed_steer_control as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_lqr_steer_control.py b/tests/test_lqr_steer_control.py
index 4807afef6c..24427a8ffd 100644
--- a/tests/test_lqr_steer_control.py
+++ b/tests/test_lqr_steer_control.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
-
-import sys
-sys.path.append("./PathTracking/lqr_steer_control/")
-
+import conftest # Add root path to sys.path
from PathTracking.lqr_steer_control import lqr_steer_control as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_model_predictive_speed_and_steer_control.py b/tests/test_model_predictive_speed_and_steer_control.py
index 4356fd40e2..9bc8ccf31c 100644
--- a/tests/test_model_predictive_speed_and_steer_control.py
+++ b/tests/test_model_predictive_speed_and_steer_control.py
@@ -1,16 +1,18 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
-import sys
-if 'cvxpy' in sys.modules: # pragma: no cover
- sys.path.append("./PathTracking/model_predictive_speed_and_steer_control/")
+from PathTracking.model_predictive_speed_and_steer_control \
+ import model_predictive_speed_and_steer_control as m
- from PathTracking.model_predictive_speed_and_steer_control import model_predictive_speed_and_steer_control as m
- print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
- class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
- m.main2()
+def test_2():
+ m.show_animation = False
+ m.main2()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_move_to_pose.py b/tests/test_move_to_pose.py
index 0125792039..e06d801555 100644
--- a/tests/test_move_to_pose.py
+++ b/tests/test_move_to_pose.py
@@ -1,12 +1,90 @@
-from unittest import TestCase
-
+import itertools
+import numpy as np
+import conftest # Add root path to sys.path
from PathTracking.move_to_pose import move_to_pose as m
-print(__file__)
+def test_random():
+ m.show_animation = False
+ m.main()
+
+
+def test_stability():
+ """
+ This unit test tests the move_to_pose.py program for stability
+ """
+ m.show_animation = False
+ x_start = 5
+ y_start = 5
+ theta_start = 0
+ x_goal = 1
+ y_goal = 4
+ theta_goal = 0
+ _, _, v_traj, w_traj = m.move_to_pose(
+ x_start, y_start, theta_start, x_goal, y_goal, theta_goal
+ )
+
+ def v_is_change(current, previous):
+ return abs(current - previous) > m.MAX_LINEAR_SPEED
+
+ def w_is_change(current, previous):
+ return abs(current - previous) > m.MAX_ANGULAR_SPEED
+
+ # Check if the speed is changing too much
+ window_size = 10
+ count_threshold = 4
+ v_change = [v_is_change(v_traj[i], v_traj[i - 1]) for i in range(1, len(v_traj))]
+ w_change = [w_is_change(w_traj[i], w_traj[i - 1]) for i in range(1, len(w_traj))]
+ for i in range(len(v_change) - window_size + 1):
+ v_window = v_change[i : i + window_size]
+ w_window = w_change[i : i + window_size]
+
+ v_unstable = sum(v_window) > count_threshold
+ w_unstable = sum(w_window) > count_threshold
+
+ assert not v_unstable, (
+ f"v_unstable in window [{i}, {i + window_size}], unstable count: {sum(v_window)}"
+ )
+ assert not w_unstable, (
+ f"w_unstable in window [{i}, {i + window_size}], unstable count: {sum(w_window)}"
+ )
+
+
+def test_reach_goal():
+ """
+ This unit test tests the move_to_pose.py program for reaching the goal
+ """
+ m.show_animation = False
+ x_start = 5
+ y_start = 5
+ theta_start_list = [0, np.pi / 2, np.pi, 3 * np.pi / 2]
+ x_goal_list = [0, 5, 10]
+ y_goal_list = [0, 5, 10]
+ theta_goal = 0
+ for theta_start, x_goal, y_goal in itertools.product(
+ theta_start_list, x_goal_list, y_goal_list
+ ):
+ x_traj, y_traj, _, _ = m.move_to_pose(
+ x_start, y_start, theta_start, x_goal, y_goal, theta_goal
+ )
+ x_diff = x_goal - x_traj[-1]
+ y_diff = y_goal - y_traj[-1]
+ rho = np.hypot(x_diff, y_diff)
+ assert rho < 0.001, (
+ f"start:[{x_start}, {y_start}, {theta_start}], goal:[{x_goal}, {y_goal}, {theta_goal}], rho: {rho} is too large"
+ )
+
+
+def test_max_speed():
+ """
+ This unit test tests the move_to_pose.py program for a MAX_LINEAR_SPEED and
+ MAX_ANGULAR_SPEED
+ """
+ m.show_animation = False
+ m.MAX_LINEAR_SPEED = 11
+ m.MAX_ANGULAR_SPEED = 5
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_move_to_pose_robot.py b/tests/test_move_to_pose_robot.py
new file mode 100644
index 0000000000..7a82f98556
--- /dev/null
+++ b/tests/test_move_to_pose_robot.py
@@ -0,0 +1,14 @@
+import conftest # Add root path to sys.path
+from PathTracking.move_to_pose import move_to_pose as m
+
+
+def test_1():
+ """
+ This unit test tests the move_to_pose_robot.py program
+ """
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_mypy_type_check.py b/tests/test_mypy_type_check.py
new file mode 100644
index 0000000000..6b933c1011
--- /dev/null
+++ b/tests/test_mypy_type_check.py
@@ -0,0 +1,50 @@
+import os
+import subprocess
+
+import conftest
+
+SUBPACKAGE_LIST = [
+ "AerialNavigation",
+ "ArmNavigation",
+ "Bipedal",
+ "Localization",
+ "Mapping",
+ "PathPlanning",
+ "PathTracking",
+ "SLAM",
+ "InvertedPendulum"
+]
+
+
+def run_mypy(dir_name, project_path, config_path):
+ res = subprocess.run(
+ ['mypy',
+ '--config-file',
+ config_path,
+ '-p',
+ dir_name],
+ cwd=project_path,
+ stdout=subprocess.PIPE,
+ encoding='utf-8')
+ return res.returncode, res.stdout
+
+
+def test():
+ project_dir_path = os.path.dirname(
+ os.path.dirname(os.path.abspath(__file__)))
+ print(f"{project_dir_path=}")
+
+ config_path = os.path.join(project_dir_path, "mypy.ini")
+ print(f"{config_path=}")
+
+ for sub_package_name in SUBPACKAGE_LIST:
+ rc, errors = run_mypy(sub_package_name, project_dir_path, config_path)
+ if errors:
+ print(errors)
+ else:
+ print("No lint errors found.")
+ assert rc == 0
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_n_joint_arm_to_point_control.py b/tests/test_n_joint_arm_to_point_control.py
index e39883559a..1d886d3670 100644
--- a/tests/test_n_joint_arm_to_point_control.py
+++ b/tests/test_n_joint_arm_to_point_control.py
@@ -1,14 +1,15 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from ArmNavigation.n_joint_arm_to_point_control\
+ import n_joint_arm_to_point_control as m
+import random
-import sys
-sys.path.append("./ArmNavigation/n_joint_arm_to_point_control/")
+random.seed(12345)
-from ArmNavigation.n_joint_arm_to_point_control import n_joint_arm_to_point_control as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.animation()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.animation()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_normal_vector_estimation.py b/tests/test_normal_vector_estimation.py
new file mode 100644
index 0000000000..7612f22aa7
--- /dev/null
+++ b/tests/test_normal_vector_estimation.py
@@ -0,0 +1,19 @@
+import conftest # Add root path to sys.path
+from Mapping.normal_vector_estimation import normal_vector_estimation as m
+import random
+
+random.seed(12345)
+
+
+def test_1():
+ m.show_animation = False
+ m.main1()
+
+
+def test_2():
+ m.show_animation = False
+ m.main2()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_particle_filter.py b/tests/test_particle_filter.py
index 3e65503976..13a20f602a 100644
--- a/tests/test_particle_filter.py
+++ b/tests/test_particle_filter.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest # Add root path to sys.path
from Localization.particle_filter import particle_filter as m
-print(__file__)
+def test_1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_point_cloud_sampling.py b/tests/test_point_cloud_sampling.py
new file mode 100644
index 0000000000..8f6447c69c
--- /dev/null
+++ b/tests/test_point_cloud_sampling.py
@@ -0,0 +1,15 @@
+import conftest # Add root path to sys.path
+from Mapping.point_cloud_sampling import point_cloud_sampling as m
+
+
+def test_1(capsys):
+ m.do_plot = False
+ m.main()
+ captured = capsys.readouterr()
+ assert "voxel_sampling_points.shape=(27, 3)" in captured.out
+ assert "farthest_sampling_points.shape=(20, 3)" in captured.out
+ assert "poisson_disk_points.shape=(20, 3)" in captured.out
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_potential_field_planning.py b/tests/test_potential_field_planning.py
index 58b960363e..ce178d793d 100644
--- a/tests/test_potential_field_planning.py
+++ b/tests/test_potential_field_planning.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest # Add root path to sys.path
from PathPlanning.PotentialFieldPlanning import potential_field_planning as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_priority_based_planner.py b/tests/test_priority_based_planner.py
new file mode 100644
index 0000000000..e2ff602d88
--- /dev/null
+++ b/tests/test_priority_based_planner.py
@@ -0,0 +1,39 @@
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ NodePath,
+ ObstacleArrangement,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning.BaseClasses import StartAndGoal
+from PathPlanning.TimeBasedPathPlanning import PriorityBasedPlanner as m
+from PathPlanning.TimeBasedPathPlanning.SafeInterval import SafeIntervalPathPlanner
+import numpy as np
+import conftest
+
+
+def test_1():
+ grid_side_length = 21
+
+ start_and_goals = [StartAndGoal(i, Position(1, i), Position(19, 19-i)) for i in range(1, 16)]
+ obstacle_avoid_points = [pos for item in start_and_goals for pos in (item.start, item.goal)]
+
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ num_obstacles=250,
+ obstacle_avoid_points=obstacle_avoid_points,
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ )
+
+ m.show_animation = False
+
+ start_and_goals: list[StartAndGoal]
+ paths: list[NodePath]
+ start_and_goals, paths = m.PriorityBasedPlanner.plan(grid, start_and_goals, SafeIntervalPathPlanner, False)
+
+ # All paths should start at the specified position and reach the goal
+ for i, start_and_goal in enumerate(start_and_goals):
+ assert paths[i].path[0].position == start_and_goal.start
+ assert paths[i].path[-1].position == start_and_goal.goal
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_probabilistic_road_map.py b/tests/test_probabilistic_road_map.py
index 7b2f1fc557..6c5eb540b1 100644
--- a/tests/test_probabilistic_road_map.py
+++ b/tests/test_probabilistic_road_map.py
@@ -1,9 +1,12 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+import numpy as np
from PathPlanning.ProbabilisticRoadMap import probabilistic_road_map
-class Test(TestCase):
+def test1():
+ probabilistic_road_map.show_animation = False
+ probabilistic_road_map.main(rng=np.random.default_rng(1233))
- def test1(self):
- probabilistic_road_map.show_animation = False
- probabilistic_road_map.main()
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_pure_pursuit.py b/tests/test_pure_pursuit.py
index 8803bba458..89c1829514 100644
--- a/tests/test_pure_pursuit.py
+++ b/tests/test_pure_pursuit.py
@@ -1,11 +1,15 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
from PathTracking.pure_pursuit import pure_pursuit as m
-print("pure_pursuit test")
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
+def test_backward():
+ m.show_animation = False
+ m.is_reverse_mode = True
+ m.main()
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_quintic_polynomials_planner.py b/tests/test_quintic_polynomials_planner.py
index 0f8d781071..43f3c6bada 100644
--- a/tests/test_quintic_polynomials_planner.py
+++ b/tests/test_quintic_polynomials_planner.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest # Add root path to sys.path
from PathPlanning.QuinticPolynomialsPlanner import quintic_polynomials_planner as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_ray_casting_grid_map.py b/tests/test_ray_casting_grid_map.py
new file mode 100644
index 0000000000..2d192c9310
--- /dev/null
+++ b/tests/test_ray_casting_grid_map.py
@@ -0,0 +1,11 @@
+import conftest # Add root path to sys.path
+from Mapping.ray_casting_grid_map import ray_casting_grid_map as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_raycasting_grid_map.py b/tests/test_raycasting_grid_map.py
deleted file mode 100644
index 3c77096bd0..0000000000
--- a/tests/test_raycasting_grid_map.py
+++ /dev/null
@@ -1,12 +0,0 @@
-from unittest import TestCase
-
-from Mapping.raycasting_grid_map import raycasting_grid_map as m
-
-print(__file__)
-
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
diff --git a/tests/test_rear_wheel_feedback.py b/tests/test_rear_wheel_feedback.py
index 7fba28bd6d..eccde52358 100644
--- a/tests/test_rear_wheel_feedback.py
+++ b/tests/test_rear_wheel_feedback.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathTracking.rear_wheel_feedback_control import rear_wheel_feedback_control as m
-import sys
-sys.path.append("./PathTracking/rear_wheel_feedback/")
-from PathTracking.rear_wheel_feedback import rear_wheel_feedback as m
+def test1():
+ m.show_animation = False
+ m.main()
-print(__file__)
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rectangle_fitting.py b/tests/test_rectangle_fitting.py
new file mode 100644
index 0000000000..cb28b6035e
--- /dev/null
+++ b/tests/test_rectangle_fitting.py
@@ -0,0 +1,11 @@
+import conftest # Add root path to sys.path
+from Mapping.rectangle_fitting import rectangle_fitting as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_reeds_shepp_path_planning.py b/tests/test_reeds_shepp_path_planning.py
index bc4a038cbb..34ccfe7730 100644
--- a/tests/test_reeds_shepp_path_planning.py
+++ b/tests/test_reeds_shepp_path_planning.py
@@ -1,9 +1,57 @@
-from unittest import TestCase
+import numpy as np
+
+import conftest # Add root path to sys.path
from PathPlanning.ReedsSheppPath import reeds_shepp_path_planning as m
-class Test(TestCase):
+def check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x,
+ end_y, end_yaw):
+ assert (abs(px[0] - start_x) <= 0.01)
+ assert (abs(py[0] - start_y) <= 0.01)
+ assert (abs(pyaw[0] - start_yaw) <= 0.01)
+ assert (abs(px[-1] - end_x) <= 0.01)
+ assert (abs(py[-1] - end_y) <= 0.01)
+ assert (abs(pyaw[-1] - end_yaw) <= 0.01)
+
+
+def check_path_length(px, py, lengths):
+ sum_len = sum(abs(length) for length in lengths)
+ dpx = np.diff(px)
+ dpy = np.diff(py)
+ actual_len = sum(
+ np.hypot(dx, dy) for (dx, dy) in zip(dpx, dpy))
+ diff_len = sum_len - actual_len
+ assert (diff_len <= 0.01)
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+def test2():
+ N_TEST = 10
+ np.random.seed(1234)
+
+ for i in range(N_TEST):
+ start_x = (np.random.rand() - 0.5) * 10.0 # [m]
+ start_y = (np.random.rand() - 0.5) * 10.0 # [m]
+ start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+
+ end_x = (np.random.rand() - 0.5) * 10.0 # [m]
+ end_y = (np.random.rand() - 0.5) * 10.0 # [m]
+ end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad]
+
+ curvature = 1.0 / (np.random.rand() * 5.0)
+
+ px, py, pyaw, mode, lengths = m.reeds_shepp_path_planning(
+ start_x, start_y, start_yaw,
+ end_x, end_y, end_yaw, curvature)
+
+ check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x,
+ end_y, end_yaw)
+ check_path_length(px, py, lengths)
+
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rocket_powered_landing.py b/tests/test_rocket_powered_landing.py
index 96cebbfe96..2f294c74cf 100644
--- a/tests/test_rocket_powered_landing.py
+++ b/tests/test_rocket_powered_landing.py
@@ -1,15 +1,20 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+import numpy as np
+from numpy.testing import suppress_warnings
-import sys
+from AerialNavigation.rocket_powered_landing import rocket_powered_landing as m
-if 'cvxpy' in sys.modules: # pragma: no cover
- sys.path.append("./AerialNavigation/rocket_powered_landing/")
- from AerialNavigation.rocket_powered_landing import rocket_powered_landing as m
- print(__file__)
+def test1():
+ m.show_animation = False
+ with suppress_warnings() as sup:
+ sup.filter(UserWarning,
+ "You are solving a parameterized problem that is not DPP"
+ )
+ sup.filter(UserWarning,
+ "Solution may be inaccurate")
+ m.main(rng=np.random.default_rng(1234))
- class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt.py b/tests/test_rrt.py
index b0c1504a32..14a8175931 100644
--- a/tests/test_rrt.py
+++ b/tests/test_rrt.py
@@ -1,30 +1,21 @@
-from unittest import TestCase
+import conftest
+import random
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../")
-try:
- from PathPlanning.RRT import simple_rrt as m
- from PathPlanning.RRT import rrt_with_pathsmoothing as m1
-except:
- raise
+from PathPlanning.RRT import rrt as m
+from PathPlanning.RRT import rrt_with_pathsmoothing as m1
+random.seed(12345)
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main(gx=1.0, gy=1.0)
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main(gx=1.0, gy=1.0)
+def test2():
+ m1.show_animation = False
+ m1.main()
- def test2(self):
- m1.show_animation = False
- m1.main()
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
- test.test2()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_dubins.py b/tests/test_rrt_dubins.py
index 19983252ef..66130484bc 100644
--- a/tests/test_rrt_dubins.py
+++ b/tests/test_rrt_dubins.py
@@ -1,27 +1,11 @@
-from unittest import TestCase
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/RRTDubins/")
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/DubinsPath/")
+import conftest # Add root path to sys.path
+from PathPlanning.RRTDubins import rrt_dubins as m
-try:
- import rrt_dubins as m
-except:
- raise
+def test1():
+ m.show_animation = False
+ m.main()
-print(__file__)
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_star.py b/tests/test_rrt_star.py
index 2171402c9b..232995ecb4 100644
--- a/tests/test_rrt_star.py
+++ b/tests/test_rrt_star.py
@@ -1,26 +1,36 @@
-import os
-import sys
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathPlanning.RRTStar import rrt_star as m
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/RRTstar/")
-try:
- import rrt_star as m
-except:
- raise
+def test1():
+ m.show_animation = False
+ m.main()
-print(__file__)
+def test_no_obstacle():
+ obstacle_list = []
+ # Set Initial parameters
+ rrt_star = m.RRTStar(start=[0, 0],
+ goal=[6, 10],
+ rand_area=[-2, 15],
+ obstacle_list=obstacle_list)
+ path = rrt_star.planning(animation=False)
+ assert path is not None
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+def test_no_obstacle_and_robot_radius():
+ obstacle_list = []
+ # Set Initial parameters
+ rrt_star = m.RRTStar(start=[0, 0],
+ goal=[6, 10],
+ rand_area=[-2, 15],
+ obstacle_list=obstacle_list,
+ robot_radius=0.8)
+ path = rrt_star.planning(animation=False)
+ assert path is not None
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_star_dubins.py b/tests/test_rrt_star_dubins.py
index 8ee3d38788..c55ca23e43 100644
--- a/tests/test_rrt_star_dubins.py
+++ b/tests/test_rrt_star_dubins.py
@@ -1,25 +1,11 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathPlanning.RRTStarDubins import rrt_star_dubins as m
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../PathPlanning/RRTStarDubins/")
-try:
- import rrt_star_dubins as m
-except:
- raise
+def test1():
+ m.show_animation = False
+ m.main()
-print(__file__)
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_star_reeds_shepp.py b/tests/test_rrt_star_reeds_shepp.py
index 4a1fa132fe..11157aa57a 100644
--- a/tests/test_rrt_star_reeds_shepp.py
+++ b/tests/test_rrt_star_reeds_shepp.py
@@ -1,28 +1,46 @@
-from unittest import TestCase
-
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../PathPlanning/RRTStarReedsShepp/")
-sys.path.append(os.path.dirname(os.path.abspath(__file__))
- + "/../PathPlanning/ReedsSheppPath/")
-
-try:
- import rrt_star_reeds_shepp as m
-except:
- raise
-
-
-print(__file__)
-
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main(maxIter=5)
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+import conftest # Add root path to sys.path
+from PathPlanning.RRTStarReedsShepp import rrt_star_reeds_shepp as m
+
+
+def test1():
+ m.show_animation = False
+ m.main(max_iter=5)
+
+obstacleList = [
+ (5, 5, 1),
+ (4, 6, 1),
+ (4, 8, 1),
+ (4, 10, 1),
+ (6, 5, 1),
+ (7, 5, 1),
+ (8, 6, 1),
+ (8, 8, 1),
+ (8, 10, 1)
+] # [x,y,size(radius)]
+
+start = [0.0, 0.0, m.np.deg2rad(0.0)]
+goal = [6.0, 7.0, m.np.deg2rad(90.0)]
+
+def test2():
+ step_size = 0.2
+ rrt_star_reeds_shepp = m.RRTStarReedsShepp(start, goal,
+ obstacleList, [-2.0, 15.0],
+ max_iter=100, step_size=step_size)
+ rrt_star_reeds_shepp.set_random_seed(seed=8)
+ path = rrt_star_reeds_shepp.planning(animation=False)
+ for i in range(len(path)-1):
+ # + 0.00000000000001 for acceptable errors arising from the planning process
+ assert m.math.dist(path[i][0:2], path[i+1][0:2]) < step_size + 0.00000000000001
+
+def test_too_big_step_size():
+ step_size = 20
+ rrt_star_reeds_shepp = m.RRTStarReedsShepp(start, goal,
+ obstacleList, [-2.0, 15.0],
+ max_iter=100, step_size=step_size)
+ rrt_star_reeds_shepp.set_random_seed(seed=8)
+ path = rrt_star_reeds_shepp.planning(animation=False)
+ assert path is None
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_star_seven_joint_arm.py b/tests/test_rrt_star_seven_joint_arm.py
new file mode 100644
index 0000000000..2f6622cf6c
--- /dev/null
+++ b/tests/test_rrt_star_seven_joint_arm.py
@@ -0,0 +1,12 @@
+import conftest # Add root path to sys.path
+from ArmNavigation.rrt_star_seven_joint_arm_control \
+ import rrt_star_seven_joint_arm_control as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_with_pathsmoothing_radius.py b/tests/test_rrt_with_pathsmoothing_radius.py
new file mode 100644
index 0000000000..a1159255b5
--- /dev/null
+++ b/tests/test_rrt_with_pathsmoothing_radius.py
@@ -0,0 +1,48 @@
+import conftest
+import math
+
+from PathPlanning.RRT import rrt_with_pathsmoothing as rrt_module
+
+def test_smoothed_path_safety():
+ # Define test environment
+ obstacle_list = [
+ (5, 5, 1.0),
+ (3, 6, 2.0),
+ (3, 8, 2.0),
+ (3, 10, 2.0),
+ (7, 5, 2.0),
+ (9, 5, 2.0)
+ ]
+ robot_radius = 0.5
+
+ # Disable animation for testing
+ rrt_module.show_animation = False
+
+ # Create RRT planner
+ rrt = rrt_module.RRT(
+ start=[0, 0],
+ goal=[6, 10],
+ rand_area=[-2, 15],
+ obstacle_list=obstacle_list,
+ robot_radius=robot_radius
+ )
+
+ # Run RRT
+ path = rrt.planning(animation=False)
+
+ # Smooth the path
+ smoothed = rrt_module.path_smoothing(path, max_iter=1000,
+ obstacle_list=obstacle_list,
+ robot_radius=robot_radius)
+
+ # Check if all points on the smoothed path are safely distant from obstacles
+ for x, y in smoothed:
+ for ox, oy, obs_radius in obstacle_list:
+ d = math.hypot(x - ox, y - oy)
+ min_safe_dist = obs_radius + robot_radius
+ assert d > min_safe_dist, \
+ f"Point ({x:.2f}, {y:.2f}) too close to obstacle at ({ox}, {oy})"
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_rrt_with_sobol_sampler.py b/tests/test_rrt_with_sobol_sampler.py
new file mode 100644
index 0000000000..affe2b165a
--- /dev/null
+++ b/tests/test_rrt_with_sobol_sampler.py
@@ -0,0 +1,14 @@
+import conftest # Add root path to sys.path
+from PathPlanning.RRT import rrt_with_sobol_sampler as m
+import random
+
+random.seed(12345)
+
+
+def test1():
+ m.show_animation = False
+ m.main(gx=1.0, gy=1.0)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_safe_interval_path_planner.py b/tests/test_safe_interval_path_planner.py
new file mode 100644
index 0000000000..bbcd4e427c
--- /dev/null
+++ b/tests/test_safe_interval_path_planner.py
@@ -0,0 +1,31 @@
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ ObstacleArrangement,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning import SafeInterval as m
+import numpy as np
+import conftest
+
+
+def test_1():
+ start = Position(1, 11)
+ goal = Position(19, 19)
+ grid_side_length = 21
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ )
+
+ m.show_animation = False
+ path = m.SafeIntervalPathPlanner.plan(grid, start, goal)
+
+ # path should have 31 entries
+ assert len(path.path) == 31
+
+ # path should end at the goal
+ assert path.path[-1].position == goal
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_space_time_astar.py b/tests/test_space_time_astar.py
new file mode 100644
index 0000000000..1194c61d2e
--- /dev/null
+++ b/tests/test_space_time_astar.py
@@ -0,0 +1,32 @@
+from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import (
+ Grid,
+ ObstacleArrangement,
+ Position,
+)
+from PathPlanning.TimeBasedPathPlanning import SpaceTimeAStar as m
+import numpy as np
+import conftest
+
+
+def test_1():
+ start = Position(1, 11)
+ goal = Position(19, 19)
+ grid_side_length = 21
+ grid = Grid(
+ np.array([grid_side_length, grid_side_length]),
+ obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1,
+ )
+
+ m.show_animation = False
+ path = m.SpaceTimeAStar.plan(grid, start, goal)
+
+ # path should have 28 entries
+ assert len(path.path) == 31
+
+ # path should end at the goal
+ assert path.path[-1].position == goal
+
+ assert path.expanded_node_count < 1000
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_spiral_spanning_tree_coverage_path_planner.py b/tests/test_spiral_spanning_tree_coverage_path_planner.py
new file mode 100644
index 0000000000..44170fa4cc
--- /dev/null
+++ b/tests/test_spiral_spanning_tree_coverage_path_planner.py
@@ -0,0 +1,58 @@
+import conftest # Add root path to sys.path
+import os
+import matplotlib.pyplot as plt
+from PathPlanning.SpiralSpanningTreeCPP \
+ import spiral_spanning_tree_coverage_path_planner
+
+spiral_spanning_tree_coverage_path_planner.do_animation = True
+
+
+def spiral_stc_cpp(img, start):
+ num_free = 0
+ for i in range(img.shape[0]):
+ for j in range(img.shape[1]):
+ num_free += img[i][j]
+
+ STC_planner = spiral_spanning_tree_coverage_path_planner.\
+ SpiralSpanningTreeCoveragePlanner(img)
+
+ edge, route, path = STC_planner.plan(start)
+
+ covered_nodes = set()
+ for p, q in edge:
+ covered_nodes.add(p)
+ covered_nodes.add(q)
+
+ # assert complete coverage
+ assert len(covered_nodes) == num_free / 4
+
+
+def test_spiral_stc_cpp_1():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + \
+ "/../PathPlanning/SpiralSpanningTreeCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test.png'))
+ start = (0, 0)
+ spiral_stc_cpp(img, start)
+
+
+def test_spiral_stc_cpp_2():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + \
+ "/../PathPlanning/SpiralSpanningTreeCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test_2.png'))
+ start = (10, 0)
+ spiral_stc_cpp(img, start)
+
+
+def test_spiral_stc_cpp_3():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + \
+ "/../PathPlanning/SpiralSpanningTreeCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test_3.png'))
+ start = (0, 0)
+ spiral_stc_cpp(img, start)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_stanley_controller.py b/tests/test_stanley_controller.py
index 5aa24acb97..bd590cb51a 100644
--- a/tests/test_stanley_controller.py
+++ b/tests/test_stanley_controller.py
@@ -1,15 +1,11 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathTracking.stanley_control import stanley_control as m
-import sys
-sys.path.append("./PathTracking/stanley_controller/")
-from PathTracking.stanley_controller import stanley_controller as m
+def test1():
+ m.show_animation = False
+ m.main()
-print(__file__)
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_state_lattice_planner.py b/tests/test_state_lattice_planner.py
index 9bf9095282..0c14222e81 100644
--- a/tests/test_state_lattice_planner.py
+++ b/tests/test_state_lattice_planner.py
@@ -1,30 +1,11 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from PathPlanning.StateLatticePlanner import state_lattice_planner as m
-import sys
-import os
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/ModelPredictiveTrajectoryGenerator/")
-sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
- "/../PathPlanning/StateLatticePlanner/")
+def test1():
+ m.show_animation = False
+ m.main()
-try:
- import state_lattice_planner as m
- import model_predictive_trajectory_generator as m2
-except:
- raise
-print(__file__)
-
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m2.show_animation = False
- m.main()
-
-
-if __name__ == '__main__': # pragma: no cover
- test = Test()
- test.test1()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_state_machine.py b/tests/test_state_machine.py
new file mode 100644
index 0000000000..e36a8120fd
--- /dev/null
+++ b/tests/test_state_machine.py
@@ -0,0 +1,51 @@
+import conftest
+
+from MissionPlanning.StateMachine.state_machine import StateMachine
+
+
+def test_transition():
+ sm = StateMachine("state_machine")
+ sm.add_transition(src_state="idle", event="start", dst_state="running")
+ sm.set_current_state("idle")
+ sm.process("start")
+ assert sm.get_current_state().name == "running"
+
+
+def test_guard():
+ class Model:
+ def can_start(self):
+ return False
+
+ sm = StateMachine("state_machine", Model())
+ sm.add_transition(
+ src_state="idle", event="start", dst_state="running", guard="can_start"
+ )
+ sm.set_current_state("idle")
+ sm.process("start")
+ assert sm.get_current_state().name == "idle"
+
+
+def test_action():
+ class Model:
+ def on_start(self):
+ self.start_called = True
+
+ model = Model()
+ sm = StateMachine("state_machine", model)
+ sm.add_transition(
+ src_state="idle", event="start", dst_state="running", action="on_start"
+ )
+ sm.set_current_state("idle")
+ sm.process("start")
+ assert model.start_called
+
+
+def test_plantuml():
+ sm = StateMachine("state_machine")
+ sm.add_transition(src_state="idle", event="start", dst_state="running")
+ sm.set_current_state("idle")
+ assert sm.generate_plantuml()
+
+
+if __name__ == "__main__":
+ conftest.run_this_test(__file__)
diff --git a/tests/test_two_joint_arm_to_point_control.py b/tests/test_two_joint_arm_to_point_control.py
index e2b9c21ac3..1de4fcd805 100644
--- a/tests/test_two_joint_arm_to_point_control.py
+++ b/tests/test_two_joint_arm_to_point_control.py
@@ -1,12 +1,12 @@
-from unittest import TestCase
+import conftest # Add root path to sys.path
+from ArmNavigation.two_joint_arm_to_point_control \
+ import two_joint_arm_to_point_control as m
-from ArmNavigation.two_joint_arm_to_point_control import two_joint_arm_to_point_control as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.animation()
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.animation()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_unscented_kalman_filter.py b/tests/test_unscented_kalman_filter.py
index 8788043e8a..b7dda6e276 100644
--- a/tests/test_unscented_kalman_filter.py
+++ b/tests/test_unscented_kalman_filter.py
@@ -1,12 +1,11 @@
-from unittest import TestCase
-
+import conftest # Add root path to sys.path
from Localization.unscented_kalman_filter import unscented_kalman_filter as m
-print(__file__)
+def test1():
+ m.show_animation = False
+ m.main()
-class Test(TestCase):
- def test1(self):
- m.show_animation = False
- m.main()
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_utils.py b/tests/test_utils.py
new file mode 100644
index 0000000000..36861c52b4
--- /dev/null
+++ b/tests/test_utils.py
@@ -0,0 +1,27 @@
+import conftest # Add root path to sys.path
+from utils import angle
+from numpy.testing import assert_allclose
+import numpy as np
+
+
+def test_rot_mat_2d():
+ assert_allclose(angle.rot_mat_2d(0.0),
+ np.array([[1., 0.],
+ [0., 1.]]))
+
+
+def test_angle_mod():
+ assert_allclose(angle.angle_mod(-4.0), 2.28318531)
+ assert(isinstance(angle.angle_mod(-4.0), float))
+ assert_allclose(angle.angle_mod([-4.0]), [2.28318531])
+ assert(isinstance(angle.angle_mod([-4.0]), np.ndarray))
+
+ assert_allclose(angle.angle_mod([-150.0, 190.0, 350], degree=True),
+ [-150., -170., -10.])
+
+ assert_allclose(angle.angle_mod(-60.0, zero_2_2pi=True, degree=True),
+ [300.])
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_visibility_road_map_planner.py b/tests/test_visibility_road_map_planner.py
new file mode 100644
index 0000000000..5a663d289d
--- /dev/null
+++ b/tests/test_visibility_road_map_planner.py
@@ -0,0 +1,11 @@
+import conftest # Add root path to sys.path
+from PathPlanning.VoronoiRoadMap import voronoi_road_map as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_voronoi_path_planner.py b/tests/test_voronoi_path_planner.py
deleted file mode 100644
index 3e0ff961d8..0000000000
--- a/tests/test_voronoi_path_planner.py
+++ /dev/null
@@ -1,11 +0,0 @@
-from unittest import TestCase
-from PathPlanning.VoronoiRoadMap import voronoi_road_map as m
-
-print(__file__)
-
-
-class Test(TestCase):
-
- def test1(self):
- m.show_animation = False
- m.main()
diff --git a/tests/test_voronoi_road_map_planner.py b/tests/test_voronoi_road_map_planner.py
new file mode 100644
index 0000000000..b0b7550fb2
--- /dev/null
+++ b/tests/test_voronoi_road_map_planner.py
@@ -0,0 +1,11 @@
+import conftest # Add root path to sys.path
+from PathPlanning.VisibilityRoadMap import visibility_road_map as m
+
+
+def test1():
+ m.show_animation = False
+ m.main()
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/tests/test_wavefront_coverage_path_planner.py b/tests/test_wavefront_coverage_path_planner.py
new file mode 100644
index 0000000000..28bb5987e7
--- /dev/null
+++ b/tests/test_wavefront_coverage_path_planner.py
@@ -0,0 +1,63 @@
+import conftest # Add root path to sys.path
+import os
+import matplotlib.pyplot as plt
+from PathPlanning.WavefrontCPP import wavefront_coverage_path_planner
+
+wavefront_coverage_path_planner.do_animation = False
+
+
+def wavefront_cpp(img, start, goal):
+ num_free = 0
+ for i in range(img.shape[0]):
+ for j in range(img.shape[1]):
+ num_free += 1 - img[i][j]
+
+ DT = wavefront_coverage_path_planner.transform(
+ img, goal, transform_type='distance')
+ DT_path = wavefront_coverage_path_planner.wavefront(DT, start, goal)
+ assert len(DT_path) == num_free # assert complete coverage
+
+ PT = wavefront_coverage_path_planner.transform(
+ img, goal, transform_type='path', alpha=0.01)
+ PT_path = wavefront_coverage_path_planner.wavefront(PT, start, goal)
+ assert len(PT_path) == num_free # assert complete coverage
+
+
+def test_wavefront_CPP_1():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test.png'))
+ img = 1 - img
+
+ start = (43, 0)
+ goal = (0, 0)
+
+ wavefront_cpp(img, start, goal)
+
+
+def test_wavefront_CPP_2():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test_2.png'))
+ img = 1 - img
+
+ start = (10, 0)
+ goal = (10, 40)
+
+ wavefront_cpp(img, start, goal)
+
+
+def test_wavefront_CPP_3():
+ img_dir = os.path.dirname(
+ os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP"
+ img = plt.imread(os.path.join(img_dir, 'map', 'test_3.png'))
+ img = 1 - img
+
+ start = (0, 0)
+ goal = (30, 30)
+
+ wavefront_cpp(img, start, goal)
+
+
+if __name__ == '__main__':
+ conftest.run_this_test(__file__)
diff --git a/users_comments.md b/users_comments.md
index 4a4f9fcb4f..c814e74c4b 100644
--- a/users_comments.md
+++ b/users_comments.md
@@ -1,11 +1,23 @@
+# User's demos
-# Educational users
+## WHILL MODEL CR with move to a pose control
+
+This is an electric wheelchair control demo by [Katsushun89](https://github.com/Katsushun89).
+
+[WHILL Model CR](https://whill.jp/model-cr) is the control target, [M5Stack](https://m5stack.com/) is used for the controller, and [toio](https://toio.io/) is used for the control input device.
+
+[Move to a Pose Control — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/6_path_tracking/move_to_a_pose/move_to_a_pose.html) is used for its control algorithm ([code link](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/move_to_pose/move_to_pose.py)).
+
+
-This is a list of users who are using PythonRobotics for education.
+Reference:
-If you found other users, please make an issue to let me know.
+- [toioと同じように動くWHILL Model CR (in Japanese)](https://qiita.com/KatsuShun89/items/68fde7544ecfe36096d2)
-- [CSCI/ARTI 4530/6530: Introduction to Robotics (Fall 2018), University of Georgia ](http://cobweb.cs.uga.edu/~ramviyas/csci_x530.html)
+
+# Educational users
+
+If you found users who are using PythonRobotics for education, please make an issue to let me know.
# Stargazers location map
@@ -22,8 +34,6 @@ This is a list of related projects.
# Individual users comments
-These are comments from user's using [](https://saythanks.io/to/AtsushiSakai)
-
---
Dear AtsushiSakai, thank you for building this cool repo for robotics. I am still learning robotics and this will give me a good starting point. I hope this note gets to you.
@@ -91,7 +101,7 @@ Thank you!
---
-Dear AtsushiSakai, Thanks a lot for the wonderful collection of projects.It was really useful. I really appreciate your time in maintaing and building this repository.It will be really great if I get a chance to meet you in person sometime.I got really inspired looking at your work. All the very best for all your future endeavors! Thanks once again,
+Dear AtsushiSakai, Thanks a lot for the wonderful collection of projects.It was really useful. I really appreciate your time in maintaining and building this repository.It will be really great if I get a chance to meet you in person sometime.I got really inspired looking at your work. All the very best for all your future endeavors! Thanks once again,
---Ezhil Bharathi
@@ -153,7 +163,7 @@ so kind of you can you make videos of it.
---
-Dear AtshshiSakai, You are very wise and smart that you created this library for students wanting to learn Probabilistic Robotics and actually perform robot control. Hats off to you and your work. I am also reading your book titled : Python Robotics
+Dear AtsushiSakai, You are very wise and smart that you created this library for students wanting to learn Probabilistic Robotics and actually perform robot control. Hats off to you and your work. I am also reading your book titled : Python Robotics
--Himanshu
@@ -253,7 +263,7 @@ Hey Atsushi We are working on a multiagent simulation game and this project
---
-Thanks a lot for this amazing set of very useful librarires!
+Thanks a lot for this amazing set of very useful libraries!
--Razvan Viorel Mihai
@@ -265,7 +275,7 @@ Dear Atsushi Sakai, This is probably one of the best open-source roboti
---
-hanks frnd, for ur contibusion
+Thanks friend, for your contribution
—--
@@ -275,15 +285,124 @@ Thank you for python robotics!!
---
+Great job
+
+--Anonymous
+
+---
+
+Dear Atsushi Sakai Thank you for the Python Robotics
+
+--Alex Liberzon
+
+---
+
+Thanks for your robotics repo!
+
+--Mithi
+
+---
+
+You made such a nice work. Congratulations :)
+
+--ATroya
+
+---
+
+thank you for python path finding repo
+
+--fengzongbao
+
+---
+
+Dear AtsushiSakai, Thank you so much for making the concept of robotics approachable for the general mass. Keep up the good work :)
+
+--Harsh Munshi
+
+---
+
+Benefit a lot for your GitHub repository of PythonRobotics. Thanks so much.
+
+--Haoran
+
+---
+
+Thanks!
+
+--Reinzor
+
+---
+
+Thanks for writing these algorithms. They are very helpful for learning robotics.
+
+--Arihant Lunawat
+
+---
+
+Dear AtsushiSakai, Thank you for providing us this great repository for playing and look around:)!
+
+--Hsin-Wen
+
+---
+
+Thanks for PythonRobotics!
+
+--Nick V
+
+---
+
+Dear AtsushiSakai, thank you so much for this material, it's so useful to me, i'm really glad with it =D
+
+--Juanda
+
+---
+
+Dear Atsushi Thanks for compiling such a vast resource for robotics motion planning.
+
+--Kartik Prakash
+
+---
+
+Thanks for your job! I have learned a lot from it!
+
+--ZhongyiShen
+
+---
+
+Dear Atsushi Sakai, Thank you so much for creating PythonRobotics and documenting it so well. I am a senior in high school trying to learn and better myself in these concepts.
+
+--Rohan Mathur
+
+
+
# Citations
1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236.
doi: 10.1109/ICCP.2018.8516589
keywords: {Automobiles;Task analysis;Autonomous vehicles;Path planning;Global Positioning System;Cameras;miniature autonomous vehicle;path planning;navigation;parking assist;lane detection and tracking;traffic sign recognition},
-URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=8516425
+URL: https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=8516425
2. Peggy (Yuchun) Wang and Caitlin Hogan, "Path Planning with Dynamic Obstacle Avoidance for a Jumping-Enabled Robot", AA228/CS238 class report, Department of Computer Science, Stanford University, URL: https://web.stanford.edu/class/aa228/reports/2018/final113.pdf
+3. Welburn, E, Hakim Khalili, H, Gupta, A, Watson, S & Carrasco, J 2019, A Navigational System for Quadcopter Remote Inspection of Offshore Substations. in The Fifteenth International Conference on Autonomic and Autonomous Systems 2019. URL:https://research.manchester.ac.uk/portal/files/107169964/ICAS19_A_Navigational_System_for_Quadcopter_Remote_Inspection_of_Offshore_Substations.pdf
+
+4. E. Horváth, C. Hajdu, C. Radu and Á. Ballagi, "Range Sensor-based Occupancy Grid Mapping with Signatures," 2019 20th International Carpathian Control Conference (ICCC), Krakow-Wieliczka, Poland, 2019, pp. 1-5.
+URL: https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=8765679
+
+5. Josie Hughes, Masaru Shimizu, and Arnoud Visser, "A Review of Robot Rescue Simulation Platforms for Robotics Education"
+URL: https://2019.robocup.org/downloads/program/HughesEtAl2019.pdf
+
+6. Hughes, Josie, Masaru Shimizu, and Arnoud Visser. "A review of robot rescue simulation platforms for robotics education." (2019).
+URL: https://www.semanticscholar.org/paper/A-Review-of-Robot-Rescue-Simulation-Platforms-for-Hughes-Shimizu/318a4bcb97a44661422ae1430d950efc408097da
+
+7. Ghosh, Ritwika, et al. "CyPhyHouse: A Programming, Simulation, and Deployment Toolchain for Heterogeneous Distributed Coordination." arXiv preprint arXiv:1910.01557 (2019).
+URL: https://arxiv.org/abs/1910.01557
+
+8. Hahn, Carsten, et al. "Dynamic Path Planning with Stable Growing Neural Gas." (2019).
+URL: https://pdfs.semanticscholar.org/5c06/f3cb9542a51e1bf1a32523c1bc7fea6cecc5.pdf
+
+9. Brijen Thananjeyan, et al. "ABC-LMPC: Safe Sample-Based Learning MPC for Stochastic Nonlinear Dynamical Systems with Adjustable Boundary Conditions"
+URL: https://arxiv.org/pdf/2003.01410
# Others
@@ -291,3 +410,6 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=85
- 36 Amazing Python Open Source Projects (v.2019) – Mybridge for Professionals https://medium.mybridge.co/36-amazing-python-open-source-projects-v-2019-2fe058d79450
+- Real-time Model Predictive Control (MPC), ACADO, Python | Work-is-Playing http://grauonline.de/wordpress/?page_id=3244
+
+- 💡 Greatest of GitHub - Python Robotics (Amazing!) - YouTube https://www.youtube.com/watch?v=f_pPaYx6Gu0&feature=emb_logo
diff --git a/utils/__init__.py b/utils/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/utils/angle.py b/utils/angle.py
new file mode 100644
index 0000000000..c9e02c5f2e
--- /dev/null
+++ b/utils/angle.py
@@ -0,0 +1,83 @@
+import numpy as np
+from scipy.spatial.transform import Rotation as Rot
+
+
+def rot_mat_2d(angle):
+ """
+ Create 2D rotation matrix from an angle
+
+ Parameters
+ ----------
+ angle :
+
+ Returns
+ -------
+ A 2D rotation matrix
+
+ Examples
+ --------
+ >>> angle_mod(-4.0)
+
+
+ """
+ return Rot.from_euler('z', angle).as_matrix()[0:2, 0:2]
+
+
+def angle_mod(x, zero_2_2pi=False, degree=False):
+ """
+ Angle modulo operation
+ Default angle modulo range is [-pi, pi)
+
+ Parameters
+ ----------
+ x : float or array_like
+ A angle or an array of angles. This array is flattened for
+ the calculation. When an angle is provided, a float angle is returned.
+ zero_2_2pi : bool, optional
+ Change angle modulo range to [0, 2pi)
+ Default is False.
+ degree : bool, optional
+ If True, then the given angles are assumed to be in degrees.
+ Default is False.
+
+ Returns
+ -------
+ ret : float or ndarray
+ an angle or an array of modulated angle.
+
+ Examples
+ --------
+ >>> angle_mod(-4.0)
+ 2.28318531
+
+ >>> angle_mod([-4.0])
+ np.array(2.28318531)
+
+ >>> angle_mod([-150.0, 190.0, 350], degree=True)
+ array([-150., -170., -10.])
+
+ >>> angle_mod(-60.0, zero_2_2pi=True, degree=True)
+ array([300.])
+
+ """
+ if isinstance(x, float):
+ is_float = True
+ else:
+ is_float = False
+
+ x = np.asarray(x).flatten()
+ if degree:
+ x = np.deg2rad(x)
+
+ if zero_2_2pi:
+ mod_angle = x % (2 * np.pi)
+ else:
+ mod_angle = (x + np.pi) % (2 * np.pi) - np.pi
+
+ if degree:
+ mod_angle = np.rad2deg(mod_angle)
+
+ if is_float:
+ return mod_angle.item()
+ else:
+ return mod_angle
diff --git a/utils/plot.py b/utils/plot.py
new file mode 100644
index 0000000000..eb5aa7ad04
--- /dev/null
+++ b/utils/plot.py
@@ -0,0 +1,234 @@
+"""
+Matplotlib based plotting utilities
+"""
+import math
+import matplotlib.pyplot as plt
+import numpy as np
+from mpl_toolkits.mplot3d import art3d
+from matplotlib.patches import FancyArrowPatch
+from mpl_toolkits.mplot3d.proj3d import proj_transform
+from mpl_toolkits.mplot3d import Axes3D
+
+from utils.angle import rot_mat_2d
+
+
+def plot_covariance_ellipse(x, y, cov, chi2=3.0, color="-r", ax=None):
+ """
+ This function plots an ellipse that represents a covariance matrix. The ellipse is centered at (x, y) and its shape, size and rotation are determined by the covariance matrix.
+
+ Parameters:
+ x : (float) The x-coordinate of the center of the ellipse.
+ y : (float) The y-coordinate of the center of the ellipse.
+ cov : (numpy.ndarray) A 2x2 covariance matrix that determines the shape, size, and rotation of the ellipse.
+ chi2 : (float, optional) A scalar value that scales the ellipse size. This value is typically set based on chi-squared distribution quantiles to achieve certain confidence levels (e.g., 3.0 corresponds to ~95% confidence for a 2D Gaussian). Defaults to 3.0.
+ color : (str, optional) The color and line style of the ellipse plot, following matplotlib conventions. Defaults to "-r" (a red solid line).
+ ax : (matplotlib.axes.Axes, optional) The Axes object to draw the ellipse on. If None (default), a new figure and axes are created.
+
+ Returns:
+ None. This function plots the covariance ellipse on the specified axes.
+ """
+ eig_val, eig_vec = np.linalg.eig(cov)
+
+ if eig_val[0] >= eig_val[1]:
+ big_ind = 0
+ small_ind = 1
+ else:
+ big_ind = 1
+ small_ind = 0
+ a = math.sqrt(chi2 * eig_val[big_ind])
+ b = math.sqrt(chi2 * eig_val[small_ind])
+ angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind])
+ plot_ellipse(x, y, a, b, angle, color=color, ax=ax)
+
+
+def plot_ellipse(x, y, a, b, angle, color="-r", ax=None, **kwargs):
+ """
+ This function plots an ellipse based on the given parameters.
+
+ Parameters
+ ----------
+ x : (float) The x-coordinate of the center of the ellipse.
+ y : (float) The y-coordinate of the center of the ellipse.
+ a : (float) The length of the semi-major axis of the ellipse.
+ b : (float) The length of the semi-minor axis of the ellipse.
+ angle : (float) The rotation angle of the ellipse, in radians.
+ color : (str, optional) The color and line style of the ellipse plot, following matplotlib conventions. Defaults to "-r" (a red solid line).
+ ax : (matplotlib.axes.Axes, optional) The Axes object to draw the ellipse on. If None (default), a new figure and axes are created.
+ **kwargs: Additional keyword arguments to pass to plt.plot or ax.plot.
+
+ Returns
+ ---------
+ None. This function plots the ellipse based on the specified parameters.
+ """
+
+ t = np.arange(0, 2 * math.pi + 0.1, 0.1)
+ px = [a * math.cos(it) for it in t]
+ py = [b * math.sin(it) for it in t]
+ fx = rot_mat_2d(angle) @ (np.array([px, py]))
+ px = np.array(fx[0, :] + x).flatten()
+ py = np.array(fx[1, :] + y).flatten()
+ if ax is None:
+ plt.plot(px, py, color, **kwargs)
+ else:
+ ax.plot(px, py, color, **kwargs)
+
+
+def plot_arrow(x, y, yaw, arrow_length=1.0,
+ origin_point_plot_style="xr",
+ head_width=0.1, fc="r", ec="k", **kwargs):
+ """
+ Plot an arrow or arrows based on 2D state (x, y, yaw)
+
+ All optional settings of matplotlib.pyplot.arrow can be used.
+ - matplotlib.pyplot.arrow:
+ https://matplotlib.org/stable/api/_as_gen/matplotlib.pyplot.arrow.html
+
+ Parameters
+ ----------
+ x : a float or array_like
+ a value or a list of arrow origin x position.
+ y : a float or array_like
+ a value or a list of arrow origin y position.
+ yaw : a float or array_like
+ a value or a list of arrow yaw angle (orientation).
+ arrow_length : a float (optional)
+ arrow length. default is 1.0
+ origin_point_plot_style : str (optional)
+ origin point plot style. If None, not plotting.
+ head_width : a float (optional)
+ arrow head width. default is 0.1
+ fc : string (optional)
+ face color
+ ec : string (optional)
+ edge color
+ """
+ if not isinstance(x, float):
+ for (i_x, i_y, i_yaw) in zip(x, y, yaw):
+ plot_arrow(i_x, i_y, i_yaw, head_width=head_width,
+ fc=fc, ec=ec, **kwargs)
+ else:
+ plt.arrow(x, y,
+ arrow_length * math.cos(yaw),
+ arrow_length * math.sin(yaw),
+ head_width=head_width,
+ fc=fc, ec=ec,
+ **kwargs)
+ if origin_point_plot_style is not None:
+ plt.plot(x, y, origin_point_plot_style)
+
+
+def plot_curvature(x_list, y_list, heading_list, curvature,
+ k=0.01, c="-c", label="Curvature"):
+ """
+ Plot curvature on 2D path. This plot is a line from the original path,
+ the lateral distance from the original path shows curvature magnitude.
+ Left turning shows right side plot, right turning shows left side plot.
+ For straight path, the curvature plot will be on the path, because
+ curvature is 0 on the straight path.
+
+ Parameters
+ ----------
+ x_list : array_like
+ x position list of the path
+ y_list : array_like
+ y position list of the path
+ heading_list : array_like
+ heading list of the path
+ curvature : array_like
+ curvature list of the path
+ k : float
+ curvature scale factor to calculate distance from the original path
+ c : string
+ color of the plot
+ label : string
+ label of the plot
+ """
+ cx = [x + d * k * np.cos(yaw - np.pi / 2.0) for x, y, yaw, d in
+ zip(x_list, y_list, heading_list, curvature)]
+ cy = [y + d * k * np.sin(yaw - np.pi / 2.0) for x, y, yaw, d in
+ zip(x_list, y_list, heading_list, curvature)]
+
+ plt.plot(cx, cy, c, label=label)
+ for ix, iy, icx, icy in zip(x_list, y_list, cx, cy):
+ plt.plot([ix, icx], [iy, icy], c)
+
+
+class Arrow3D(FancyArrowPatch):
+
+ def __init__(self, x, y, z, dx, dy, dz, *args, **kwargs):
+ super().__init__((0, 0), (0, 0), *args, **kwargs)
+ self._xyz = (x, y, z)
+ self._dxdydz = (dx, dy, dz)
+
+ def draw(self, renderer):
+ x1, y1, z1 = self._xyz
+ dx, dy, dz = self._dxdydz
+ x2, y2, z2 = (x1 + dx, y1 + dy, z1 + dz)
+
+ xs, ys, zs = proj_transform((x1, x2), (y1, y2), (z1, z2), self.axes.M)
+ self.set_positions((xs[0], ys[0]), (xs[1], ys[1]))
+ super().draw(renderer)
+
+ def do_3d_projection(self, renderer=None):
+ x1, y1, z1 = self._xyz
+ dx, dy, dz = self._dxdydz
+ x2, y2, z2 = (x1 + dx, y1 + dy, z1 + dz)
+
+ xs, ys, zs = proj_transform((x1, x2), (y1, y2), (z1, z2), self.axes.M)
+ self.set_positions((xs[0], ys[0]), (xs[1], ys[1]))
+
+ return np.min(zs)
+
+
+def _arrow3D(ax, x, y, z, dx, dy, dz, *args, **kwargs):
+ '''Add an 3d arrow to an `Axes3D` instance.'''
+ arrow = Arrow3D(x, y, z, dx, dy, dz, *args, **kwargs)
+ ax.add_artist(arrow)
+
+
+def plot_3d_vector_arrow(ax, p1, p2):
+ setattr(Axes3D, 'arrow3D', _arrow3D)
+ ax.arrow3D(p1[0], p1[1], p1[2],
+ p2[0]-p1[0], p2[1]-p1[1], p2[2]-p1[2],
+ mutation_scale=20,
+ arrowstyle="-|>",
+ )
+
+
+def plot_triangle(p1, p2, p3, ax):
+ ax.add_collection3d(art3d.Poly3DCollection([[p1, p2, p3]], color='b'))
+
+
+def set_equal_3d_axis(ax, x_lims, y_lims, z_lims):
+ """Helper function to set equal axis
+
+ Args:
+ ax (Axes3DSubplot): matplotlib 3D axis, created by
+ `ax = fig.add_subplot(projection='3d')`
+ x_lims (np.array): array containing min and max value of x
+ y_lims (np.array): array containing min and max value of y
+ z_lims (np.array): array containing min and max value of z
+ """
+ x_lims = np.asarray(x_lims)
+ y_lims = np.asarray(y_lims)
+ z_lims = np.asarray(z_lims)
+ # compute max required range
+ max_range = np.array([x_lims.max() - x_lims.min(),
+ y_lims.max() - y_lims.min(),
+ z_lims.max() - z_lims.min()]).max() / 2.0
+ # compute mid-point along each axis
+ mid_x = (x_lims.max() + x_lims.min()) * 0.5
+ mid_y = (y_lims.max() + y_lims.min()) * 0.5
+ mid_z = (z_lims.max() + z_lims.min()) * 0.5
+
+ # set limits to axis
+ ax.set_xlim(mid_x - max_range, mid_x + max_range)
+ ax.set_ylim(mid_y - max_range, mid_y + max_range)
+ ax.set_zlim(mid_z - max_range, mid_z + max_range)
+
+
+if __name__ == '__main__':
+ plot_ellipse(0, 0, 1, 2, np.deg2rad(15))
+ plt.axis('equal')
+ plt.show()
+