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

Owner
Atsushi Sakai
An autonomous navigation system engineer #C++ #ROS #MATLAB #Python #Vim #Robotics #AutonomousDriving #Optimization #ModelPredictiveControl #julialang
Atsushi Sakai
Minimal pure Python library for working with little-endian list representation of bit strings.

bitlist Minimal Python library for working with bit vectors natively. Purpose This library allows programmers to work with a native representation of

Andrei Lapets 0 Jul 25, 2022
Distributed Grid Descent: an algorithm for hyperparameter tuning guided by Bayesian inference, designed to run on multiple processes and potentially many machines with no central point of control

Distributed Grid Descent: an algorithm for hyperparameter tuning guided by Bayesian inference, designed to run on multiple processes and potentially many machines with no central point of control.

Martin 1 Jan 01, 2022
A raw implementation of the nearest insertion algorithm to resolve TSP problems in a TXT format.

TSP-Nearest-Insertion A raw implementation of the nearest insertion algorithm to resolve TSP problems in a TXT format. Instructions Load a txt file wi

sjas_Phantom 1 Dec 02, 2021
Rover. Finding the shortest pass by Dijkstra’s shortest path algorithm

rover Rover. Finding the shortest path by Dijkstra’s shortest path algorithm Задача Вы — инженер, проектирующий роверы-беспилотники. Вам надо спроекти

1 Nov 11, 2021
PICO is an algorithm for exploiting Reinforcement Learning (RL) on Multi-agent Path Finding tasks.

PICO is an algorithm for exploiting Reinforcement Learning (RL) on Multi-agent Path Finding tasks. It is developed by the Multi-Agent Artificial Intel

21 Dec 20, 2022
Xor encryption and decryption algorithm

Folosire: Pentru encriptare: python encrypt.py parola fișier pentru criptare fișier encriptat(de tip binar) Pentru decriptare: python decrypt.p

2 Dec 05, 2021
Python-Strongest-Encrypter - Transform your text into encrypted symbols using their dictionary

How does the encrypter works? Transform your text into encrypted symbols using t

1 Jul 10, 2022
The DarkRift2 networking framework written in Python 3

DarkRiftPy is Darkrift2 written in Python 3. The implementation is fully compatible with the original version. So you can write a client side on Python that connects to a Darkrift2 server written in

Anton Dobryakov 6 May 23, 2022
A calculator to test numbers against the collatz conjecture

The Collatz Calculator This is an algorithm custom built by Kyle Dickey, used to test numbers against the simple rules of the Collatz Conjecture. Get

Kyle Dickey 2 Jun 14, 2022
This repository is an individual project made at BME with the topic of self-driving car simulator and control algorithm.

BME individual project - NEAT based self-driving car This repository is an individual project made at BME with the topic of self-driving car simulator

NGO ANH TUAN 1 Dec 13, 2021
8-puzzle-solver with UCS, ILS, IDA* algorithm

Eight Puzzle 8-puzzle-solver with UCS, ILS, IDA* algorithm pre-usage requirements python3 python3-pip virtualenv prepare enviroment virtualenv -p pyth

Mohsen Arzani 4 Sep 22, 2021
Wordle-solver - A program that solves a Wordle using a simple algorithm

Wordle Solver A program that solves a Wordle using a simple algorithm. To see it

Luc Bouchard 3 Feb 13, 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

50 Dec 06, 2022
Classic algorithms including Fizz Buzz, Bubble Sort, the Fibonacci Sequence, a Sudoku solver, and more.

Algorithms Classic algorithms including Fizz Buzz, Bubble Sort, the Fibonacci Sequence, a Sudoku solver, and more. Algorithm Complexity Time and Space

1 Jan 14, 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 01, 2021
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 e

Jaswinder Singh 168 Dec 30, 2022
A GUI visualization of QuickSort algorithm

QQuickSort A simple GUI visualization of QuickSort algorithm. It only uses PySide6, it does not have any other external dependency. How to run Install

Jaime R. 2 Dec 24, 2021
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 06, 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 generatio

Mahdi Hassanzadeh 4 Dec 24, 2022
marching rectangles algorithm in python with clean code.

Marching Rectangles marching rectangles algorithm in python with clean code. Tools Python 3 EasyDraw Creators Mohammad Dori Run the Code Installation

Mohammad Dori 3 Jul 15, 2022