Python codes for robotics algorithm.
- What is this?
- Requirements
- Documentation
- How to use
- Localization
- Mapping
- SLAM
- Path Planning
- Path Tracking
- Arm Navigation
- Aerial Navigation
- Bipedal
- License
- Use-case
- Contribution
- Citing
- Support
- Authors
This is a Python code collection of robotics algorithms, especially for autonomous navigation.
Features:
- 
Easy to read for understanding each algorithm's basic idea. 
- 
Widely used and practical algorithms are selected. 
- 
Minimum dependency. 
See this paper for more details:
- 
Python 3.7.x (2.7 is not supported) 
- 
numpy 
- 
scipy 
- 
matplotlib 
- 
pandas 
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
- Clone this repo.
git clone https://github.com/AtsushiSakai/PythonRobotics.git
cd PythonRobotics/
- Install the required libraries. You can use environment.yml with conda command.
conda env create -f environment.yml
- 
Execute python script in each directory. 
- 
Add star to this repo if you like it 😃. 
Documentation: Notebook
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:
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:
This is a 2D Gaussian grid mapping example.
This is a 2D ray casting grid mapping example.
This example shows how to convert a 2D range measurement to a grid map.
This is a 2D object clustering with k-means algorithm.
This is a 2D rectangle fitting for vehicle detection.
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.
Ref:
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.
Ref:
This is a graph based 2D pose optimization SLAM example.
This is a graph based 3D pose optimization SLAM example.
This is a 2D navigation sample code with Dynamic Window Approach.
This is a 2D grid based shortest path planning with Dijkstra's algorithm.
In the animation, cyan points are searched nodes.
This is a 2D grid based shortest path planning with A star algorithm.
In the animation, cyan points are searched nodes.
Its heuristic is 2D Euclid distance.
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:
This is a 2D grid based coverage path planning simulation.
This script is a path planning code with state lattice planning.
This code uses the model predictive trajectory generator to solve boundary problem.
Ref:
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:
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:
Path planning for a car robot with RRT* and reeds shepp path planner.
This is a path planning simulation with LQR-RRT*.
A double integrator motion model is used for LQR local planner.
Ref:
Motion planning with quintic polynomials.
It can calculate 2D path, velocity, and acceleration profile based on quintic polynomials.
Ref:
A sample code with Reeds Shepp path planning.
Ref:
A sample code using LQR based path planning for double integrator model.
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 
This is a simulation of moving to a pose control
Ref:
Path tracking simulation with Stanley steering control and PID speed control.
Ref:
Path tracking simulation with rear wheel feedback steering control and PID speed control.
Ref:
Path tracking simulation with LQR speed and steering control.
Ref:
Path tracking simulation with iterative linear model predictive speed and steering control.
Ref:
A motion planning and path tracking simulation with NMPC of C-GMRES
Ref:
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.
In this simulation N = 10, however, you can change it.
Arm navigation with obstacle avoidance simulation.
This is a 3d trajectory following simulation for a quadrotor.
This is a 3d trajectory generation simulation for a rocket powered landing.
Ref:
This is a bipedal planner for modifying footsteps with inverted pendulum.
You can set the footsteps and the planner will modify those automatically.
MIT
If this project helps your robotics project, please let me know with .
Your robot's video, which is using PythonRobotics, is very welcome!!
This is a list of other user's comment and references:users_comments
A small PR like bug fix is welcome.
If your PR is merged multiple times, I will add your account to the author list.
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.
If you or your company would like to support this project, please consider:
You can add your name or your company logo in README if you are a patron.
E-mail consultant is also available.
Your comment using  is also welcome.
This is a list: Users comments






































