Python sample codes for robotics algorithms.

Overview

header pic

PythonRobotics

GitHub_Action_Linux_CI GitHub_Action_MacOS_CI Build Status Documentation Status Build status codecov Language grade: Python CodeFactor tokei

Python codes for robotics algorithm.

Table of Contents

What is this?

This is a Python code collection of robotics algorithms.

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:

Requirements

For running each sample code:

  • Python 3.9.x

  • numpy

  • scipy

  • matplotlib

  • pandas

  • cvxpy

For development:

  • pytest (for unit tests)

  • pytest-xdist (for parallel unit tests)

  • mypy (for type check)

  • Sphinx (for document generation)

  • pycodestyle (for code style check)

Documentation

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/

All animation gifs are stored here: AtsushiSakai/PythonRoboticsGifs: Animation gifs of PythonRobotics

How to use

  1. Clone this repo.

git clone https://github.com/AtsushiSakai/PythonRobotics.git

  1. Install the required libraries.

using conda :

conda env create -f environment.yml

using pip :

pip install -r requirements.txt

  1. Execute python script in each directory.

  2. Add star to this repo if you like it 😃 .

Localization

Extended Kalman Filter localization

EKF pic

Documentation: Notebook

Particle filter localization

2

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 an estimated trajectory with PF.

It is assumed that the robot can measure a distance from landmarks (RFID).

These measurements are used for PF localization.

Ref:

Histogram filter localization

3

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:

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.

2

Lidar to grid map

This example shows how to convert a 2D range measurement to a grid map.

2

k-means object clustering

This is a 2D object clustering with k-means algorithm.

2

Rectangle fitting

This is a 2D rectangle fitting for vehicle detection.

2

SLAM

Simultaneous Localization and Mapping(SLAM) examples

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 and points.

3

Ref:

FastSLAM 1.0

This is a feature based SLAM example using FastSLAM 1.0.

The blue line is ground truth, the black line is dead reckoning, the red line is the estimated trajectory with FastSLAM.

The red points are particles of FastSLAM.

Black points are landmarks, blue crosses are estimated landmark positions by FastSLAM.

3

Ref:

Path Planning

Dynamic Window Approach

This is a 2D navigation sample code with Dynamic Window Approach.

2

Grid based search

Dijkstra algorithm

This is a 2D grid based the shortest path planning with Dijkstra's algorithm.

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

In the animation, cyan points are searched nodes.

A* algorithm

This is a 2D grid based the shortest path planning with A star algorithm.

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

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.

figure at master · nirnayroy/intelligentrobotics

The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm.

Ref:

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:

Grid based coverage path planning

This is a 2D grid based coverage path planning simulation.

PotentialField

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:

Biased polar sampling

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

Lane sampling

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

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:

  

Rapidly-Exploring Random Trees (RRT)

RRT*

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

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:

RRT* with reeds-shepp path

Robotics/animation.gif at master · AtsushiSakai/PythonRobotics)

Path planning for a car robot with RRT* and reeds shepp path planner.

LQR-RRT*

This is a path planning simulation with LQR-RRT*.

A double integrator motion model is used for LQR local planner.

LQR_RRT

Ref:

Quintic polynomials planning

Motion planning with quintic polynomials.

2

It can calculate a 2D path, velocity, and acceleration profile based on quintic polynomials.

Ref:

Reeds Shepp planning

A sample code with Reeds Shepp path planning.

RSPlanning

Ref:

LQR based path planning

A sample code using LQR based path planning for double integrator model.

RSPlanning

Optimal Trajectory in a Frenet Frame

3

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 the predicted path.

Ref:

Path Tracking

move to a pose control

This is a simulation of moving to a pose control

2

Ref:

Stanley control

Path tracking simulation with Stanley steering control and PID speed control.

2

Ref:

Rear wheel feedback control

Path tracking simulation with rear wheel feedback steering control and PID speed control.

PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics

Ref:

Linear–quadratic regulator (LQR) speed and steering control

Path tracking simulation with LQR speed and steering control.

3

Ref:

Model predictive speed and steering control

Path tracking simulation with iterative linear model predictive speed and steering control.

MPC pic

Ref:

Nonlinear Model predictive control with C-GMRES

A motion planning and path tracking simulation with NMPC of C-GMRES

3

Ref:

Arm Navigation

N joint arm to point control

N joint arm to a point control simulation.

This is an interactive simulation.

You can set the goal position of the end effector with left-click on the plotting area.

3

In this simulation N = 10, however, you can change it.

Arm navigation with obstacle avoidance

Arm navigation with obstacle avoidance simulation.

3

Aerial Navigation

drone 3d trajectory following

This is a 3d trajectory following simulation for a quadrotor.

3

rocket powered landing

This is a 3d trajectory generation simulation for a rocket powered landing.

3

Ref:

Bipedal

bipedal planner 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.

3

License

MIT

Use-case

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

Contribution

Any contribution is welcome!!

Citing

If you use this project's code for your academic work, we encourage you to cite our papers

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.

Support

If you or your company would like to support this project, please consider:

If you would like to support us in some other way, please contact with creating an issue.

Sponsors

JetBrains

They are providing a free license of their IDEs for this OSS development.

Authors

Comments
  • Dynamic Movement Primitives Implementation

    Dynamic Movement Primitives Implementation

    What does this implement/fix?

    Implements Dynamic Movement Primitives, which is a way of 'learning' a path and being able to stretch or squeeze it in space or time as the user sees fit. The path is learned as a weighted sums of gaussian distributions.

    Additional information

    I made a file and a few unit tests, but let me know if there is anything else you'd like me to add to this!

    opened by SchwartzCode 32
  • Summary paper

    Summary paper

    opened by AtsushiSakai 27
  • Add ICP support for 3d point clouds

    Add ICP support for 3d point clouds

    Reference issue

    fix #464

    What does this implement/fix?

    Adds an implementation of code for ICP to work both for 2d and 3d point clouds.

    Additional information

    Make functions icp_matching() and update_homogeneous_matrix() flexible. Depending on the current_points.shape[0] function svd_motion_estimation() automatically returns the correct size for Rt, Tt. Then, in update_homogeneous_matrix() depending on their size matrix H is formed to be 3x3 or 4x4.

    Test for 3d point cloud is provided. Made the same manner as tests for 2d point cloud.

    opened by NobleBumblebee 20
  • Add Graph SLAM documentation and SE(2) example

    Add Graph SLAM documentation and SE(2) example

    This is a work in progress.

    The Jupyter notebook doesn't render correctly on GitHub, so I moved the write-up into a LaTeX file and included both the .tex source and the generated PDF. I'll probably remove it altogether from the Jupyter notebook.

    TODO: Add code and example problem

    Related issue: https://github.com/AtsushiSakai/PythonRobotics/issues/296

    opened by JeffLIrion 18
  • Paths ignoring collision(s)...

    Paths ignoring collision(s)...

    Hi Atsushi

    Great work! I've just started exploring and playing but am getting results as in figure below. I'd expect to get "Cannot find path". Am I missing something?

    Thanks in advance.

    Cheers RRT_example

    opened by 4lexir4 18
  • Code might be wrong: the true trajectory in

    Code might be wrong: the true trajectory in "particle filter" algorithm shouldn't be a circle

    In the current code in Localization/particle_filter/particle_filter.py,
    the resultant true trajectory is a circle, as shown below: Selection_126

    (The blue line under the red line is the true trajectory, which is a circle. The figure is copied from README)

    However, due to the noise (e.g., wheel slips, noise in the motor), the true trajectory cannot be a perfect circle. So the code might be wrong.

    In my view, the "true trajectory" and "dead reckoning trajectory" needs to be swapped inside the function def observation to solve the error.

    Besides, for the random noise, I think

    np.random.randn() * Rsim[0, 0]
    

    should be replaced by:

    np.random.randn() * Rsim[0, 0]**0.5
    

    (Because Rsim is the variance)

    opened by felixchenfy 16
  • MPC have some problem

    MPC have some problem

    when i plan a path along x positive direction means zero degree.if current car's degree is 359 or 0 degree.that will cause problem .yaw error may be -359 or -1

    opened by hexiangquan 14
  • FrenetOptimalTrajectory: Following and  Low Speed Trajectories

    FrenetOptimalTrajectory: Following and Low Speed Trajectories

    I've implemented Following and Low Speed Trajectories from Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame. In order to test the algorithms, I've set up a simulation with two vehicles on a race track.

    opened by lucabonamini 13
  • KeyError in Mix Integer Path Planning

    KeyError in Mix Integer Path Planning

    Hi @AtsushiSakai , I'm interested in modifying your Mix Integer Path Planning to a multi-vehicle scenario, however I'm having troubles running your code. This is the console output when I run the code:

    mix_integer_opt_path_planning.py start!! ('time:', 0) Academic license - for non-commercial use only Traceback (most recent call last): File "mix_integer_opt_path_planning.py", line 127, in main() File "mix_integer_opt_path_planning.py", line 101, in main s_p, u_p = control(s, gs, ob) File "mix_integer_opt_path_planning.py", line 69, in control prob.solve(solver=cvxpy.GUROBI) File "/usr/local/lib/python2.7/dist-packages/cvxpy-0.4.11-py2.7.egg/cvxpy/problems/problem.py", line 209, in solve return self._solve(*args, **kwargs) File "/usr/local/lib/python2.7/dist-packages/cvxpy-0.4.11-py2.7.egg/cvxpy/problems/problem.py", line 331, in _solve kwargs) File "/usr/local/lib/python2.7/dist-packages/cvxpy-0.4.11-py2.7.egg/cvxpy/problems/solvers/gurobi_intf.py", line 229, in solve A, b) File "/usr/local/lib/python2.7/dist-packages/cvxpy-0.4.11-py2.7.egg/cvxpy/problems/solvers/gurobi_intf.py", line 326, in add_model_lin_constr expr_list[i].append((c, v)) KeyError: 206

    It has something to do with the use of the GUROBI solver, however I verified it is correctly installed already (I ran one of the examples they provide). Do you have an idea of what could be wrong? Thanks!

    opened by carlosluis 12
  • New A star algorithm pr

    New A star algorithm pr

    1. rewrite A star algorithm, improved efficiency by searching the path from two side simultaneously (i.e. from start to goal + from goal to start)

    2. generate obstacles map randomly, the number of obstacle is adjustable

    Find a path: FindPath FindPath2

    No path to the goal, indicate the boundary confine robot or goal: NoPath NoPath2

    opened by weicent 11
  • Forward Kinematics and Inverse Kinematics with 3D

    Forward Kinematics and Inverse Kinematics with 3D

    I implemented FK(Forward Kinematics) and IK(Inverse Kinematics) with 3D arm manipulator.

    You can initialize manipulator with Denavit-Hartenberg parameters.

    There are exapmles of FK and IK, random_*.py, initializing with Denavit-Hartenberg parameters of PR2 robot.

    Please advise me if you want this PR be merged.

    opened by takayuki5168 11
  • Utilize numpy to reduce calculation time

    Utilize numpy to reduce calculation time

    Change-Id: I6e421a1c2524a3d8f8875121a1a6d2ed832c3150

    Reference issue

    What does this implement/fix?

    I've noticed that the current Implementation uses lists. By replacing them with numpy arrays and using built in numpy functions such as any, I reduced the calculation time of d_star_lite. The other thing that I've noticed, once after initializing class, if the user wants to add new spoofed objects and calculate a new path, it was not using the prior information that is generated. So I modified the initialization process a bit to use the prior information.

    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)
    opened by kadirhas 1
  • Bump flake8 from 5.0.4 to 6.0.0 in /requirements

    Bump flake8 from 5.0.4 to 6.0.0 in /requirements

    Bumps flake8 from 5.0.4 to 6.0.0.

    Commits

    Dependabot compatibility score

    Dependabot will resolve any conflicts with this PR as long as you don't alter it yourself. You can also trigger a rebase manually by commenting @dependabot rebase.


    Dependabot commands and options

    You can trigger Dependabot actions by commenting on this PR:

    • @dependabot rebase will rebase this PR
    • @dependabot recreate will recreate this PR, overwriting any edits that have been made to it
    • @dependabot merge will merge this PR after your CI passes on it
    • @dependabot squash and merge will squash and merge this PR after your CI passes on it
    • @dependabot cancel merge will cancel a previously requested merge and block automerging
    • @dependabot reopen will reopen this PR if it is closed
    • @dependabot close will close this PR and stop Dependabot recreating it. You can achieve the same result by closing it manually
    • @dependabot ignore this major version will close this PR and stop Dependabot creating any more for this major version (unless you reopen the PR or upgrade to it yourself)
    • @dependabot ignore this minor version will close this PR and stop Dependabot creating any more for this minor version (unless you reopen the PR or upgrade to it yourself)
    • @dependabot ignore this dependency will close this PR and stop Dependabot creating any more for this dependency (unless you reopen the PR or upgrade to it yourself)
    dependencies 
    opened by dependabot[bot] 2
  • support python3.11

    support python3.11

    Reference issue

    fix #740

    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)
    opened by AtsushiSakai 3
  • Add setup.py for releasing package to expose common utilities in PythonRobotics.

    Add setup.py for releasing package to expose common utilities in PythonRobotics.

    I think the utilities in this package are helpful, this should be used as a package and should be installed via pip. https://github.com/AtsushiSakai/PythonRobotics/tree/master/utils

    This is the time to release as an official PyPI package. And when this package is mature, we can start to add each algorithm to the package step by step.

    opened by AtsushiSakai 1
  • Using ``*`` for matrix multiplication has been deprecated since CVXPY 1.1

    Using ``*`` for matrix multiplication has been deprecated since CVXPY 1.1

    Not a bug! Simply a note that I will work on suppressing the warnings. Thanks.

    Describe the deprecated feature warnings.warn(msg, UserWarning) /usr/local/lib/python3.10/dist-packages/cvxpy/expressions/expression.py:593: UserWarning: This use of * has resulted in matrix multiplication. Using * for matrix multiplication has been deprecated since CVXPY 1.1. Use * for matrix-scalar and vector-scalar multiplication. Use @ for matrix-matrix and matrix-vector multiplication. Use multiply for elementwise multiplication. This code path has been hit 2590 times so far.

    warnings.warn(msg, UserWarning)

    Expected behavior No warnings.

    Screenshots Working on making changes to the code to suppress the warnings; I will submit a PR if successful in due course. Thanks.

    Desktop (please complete the following information):

    • Python version 3.10
    • Each library version
    • OS version Ubunut 22.04
    help wanted 
    opened by baqwas 1
Owner
Atsushi Sakai
An autonomous navigation system engineer #C++ #ROS #MATLAB #Python #Vim #Robotics #AutonomousDriving #Optimization #ModelPredictiveControl #julialang
Atsushi Sakai
zoofs is a Python library for performing feature selection using an variety of nature inspired wrapper algorithms. The algorithms range from swarm-intelligence to physics based to Evolutionary. It's easy to use ,flexible and powerful tool to reduce your feature size.

zoofs is a Python library for performing feature selection using a variety of nature-inspired wrapper algorithms. The algorithms range from swarm-intelligence to physics-based to Evolutionary. It's easy to use , flexible and powerful tool to reduce your feature size.

Jaswinder Singh 168 Dec 30, 2022
Genetic algorithms are heuristic search algorithms inspired by the process that supports the evolution of life.

Genetic algorithms are heuristic search algorithms inspired by the process that supports the evolution of life. The algorithm is designed to replicate the natural selection process to carry generation, i.e. survival of the fittest of beings.

Mahdi Hassanzadeh 4 Dec 24, 2022
Algorithms-in-Python - Programs related to DSA in Python for placement practice

Algorithms-in-Python Programs related to DSA in Python for placement practice CO

MAINAK CHAUDHURI 2 Feb 2, 2022
Minimal examples of data structures and algorithms in Python

Pythonic Data Structures and Algorithms Minimal and clean example implementations of data structures and algorithms in Python 3. Contributing Thanks f

Keon 22k Jan 9, 2023
Repository for data structure and algorithms in Python for coding interviews

Python Data Structures and Algorithms This repository contains questions requiring implementation of data structures and algorithms concepts. It is us

Prabhu Pant 1.9k Jan 1, 2023
All Algorithms implemented in Python

The Algorithms - Python All algorithms implemented in Python (for education) These implementations are for learning purposes only. Therefore they may

The Algorithms 150.6k Jan 3, 2023
:computer: Data Structures and Algorithms in Python

Algorithms in Python Implementations of a few algorithms and datastructures for fun and profit! Completed Karatsuba Multiplication Basic Sorting Rabin

Prakhar Srivastav 2.9k Jan 1, 2023
Algorithms implemented in Python

Python Algorithms Library Laurent Luce Description The purpose of this library is to help you with common algorithms like: A* path finding. String Mat

Laurent Luce 264 Dec 6, 2022
A command line tool for memorizing algorithms in Python by typing them.

Algo Drills A command line tool for memorizing algorithms in Python by typing them. In alpha and things will change. How it works Type out an algorith

Travis Jungroth 43 Dec 2, 2022
🧬 Performant Evolutionary Algorithms For Python with Ray support

?? Performant Evolutionary Algorithms For Python with Ray support

Nathan 49 Oct 20, 2022
All algorithms implemented in Python for education

The Algorithms - Python All algorithms implemented in Python - for education Implementations are for learning purposes only. As they may be less effic

null 1 Oct 20, 2021
Implementation of Apriori algorithms via Python

Installing run bellow command for installing all packages pip install -r requirements.txt Data Put csv data under this directory "infrastructure/data

Mahdi Rezaei 0 Jul 25, 2022
A simple python application to visualize sorting algorithms.

Visualize sorting algorithms A simple python application to visualize sorting algorithms. Sort Algorithms Name Function Name O( ) Bubble Sort bubble_s

Duc Tran 3 Apr 1, 2022
Programming Foundations Algorithms With Python

Programming-Foundations-Algorithms Algorithms purpose to solve a specific proplem with a sequential sets of steps for instance : if you need to add di

omar nafea 1 Nov 1, 2021
Repository for Comparison based sorting algorithms in python

Repository for Comparison based sorting algorithms in python. This was implemented for project one submission for ITCS 6114 Data Structures and Algorithms under the guidance of Dr. Dewan at the University of North Carolina at Charlotte, Fall 2021.

Devashri Khagesh Gadgil 1 Dec 20, 2021
Python Client for Algorithmia Algorithms and Data API

Algorithmia Common Library (python) Python client library for accessing the Algorithmia API For API documentation, see the PythonDocs Algorithm Develo

Algorithmia 138 Oct 26, 2022
Algorithms and data structures for educational, demonstrational and experimental purposes.

Algorithms and Data Structures (ands) Introduction This project was created for personal use mostly while studying for an exam (starting in the month

null 50 Dec 6, 2022
This is the code repository for 40 Algorithms Every Programmer Should Know , published by Packt.

40 Algorithms Every Programmer Should Know, published by Packt

Packt 721 Jan 2, 2023
Solving a card game with three search algorithms: BFS, IDS, and A*

Search Algorithms Overview In this project, we want to solve a card game with three search algorithms. In this card game, we have to sort our cards by

Korosh 5 Aug 4, 2022