Coder Social home page Coder Social logo

atsushisakai / pythonrobotics Goto Github PK

View Code? Open in Web Editor NEW
21.7K 514.0 6.3K 295.58 MB

Python sample codes for robotics algorithms.

Home Page: https://atsushisakai.github.io/PythonRobotics/

License: Other

Python 99.97% Shell 0.03%
python robotics algorithm path-planning control animation localization slam cvxpy ekf autonomous-vehicles autonomous-driving mapping autonomous-navigation robot hacktoberfest

pythonrobotics's Introduction

header pic

PythonRobotics

GitHub_Action_Linux_CI GitHub_Action_MacOS_CI GitHub_Action_Windows_CI Build status codecov

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:

For development:

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: Welcome to PythonRobotics’s documentation! — PythonRobotics documentation

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
    
  2. Install the required libraries.

  • using conda :

    conda env create -f requirements/environment.yml
    
  • using pip :

    pip install -r requirements/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

Ref:

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:

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.

D* Lite

The animation shows a robot finding its path and rerouting to avoid obstacles as they are discovered using the D* Lite search algorithm.

Refs:

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 user's comment and references:users_comments

Contribution

Any contribution is welcome!!

Please check this document:How To Contribute — PythonRobotics documentation

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.

Supporting this project

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

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

They are providing a free license of their 1Password team license for this OSS project.

Authors

pythonrobotics's People

Contributors

abinashbunty avatar adelizer avatar araffin avatar atsushisakai avatar chachay avatar daniel-s-ingram avatar dependabot[bot] avatar drewtu2 avatar franciscomoretti avatar gjacquenot avatar goktug97 avatar guilyx avatar horverno avatar jefflirion avatar jwdinius avatar karanchawla avatar kartikmadhira1 avatar kitsunow avatar ksvbka avatar kyberszittya avatar m-dobler avatar muhammad-yazdian avatar rsasaki0109 avatar sarimmehdi avatar taka-kazu avatar takayuki5168 avatar vss2sn avatar weicent avatar y011d4 avatar yilunc2020 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

pythonrobotics's Issues

dynamic window maximum recursion depth exceeded

Hi, I just cloned your repository today and I have a problem running dynamic_window_approach.pywith this version's matplotlibrecorder
The error message is shown below

Traceback (most recent call last):
  File "dynamic_window_approach.py", line 219, in <module>
    main()
  File "dynamic_window_approach.py", line 199, in main
    plt.plot(ob[:, 0], ob[:, 1], "ok")
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/pyplot.py", line 2987, in plot
    ret = ax.plot(*args, **kwargs)
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/axes.py", line 4137, in plot
    for line in self._get_lines(*args, **kwargs):
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/axes.py", line 317, in _grab_next_args
    for seg in self._plot_args(remaining, kwargs):
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/axes.py", line 295, in _plot_args
    x, y = self._xy_from_xy(x, y)
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/axes.py", line 213, in _xy_from_xy
    bx = self.axes.xaxis.update_units(x)
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/axis.py", line 1336, in update_units
    converter = munits.registry.get_converter(data)
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/units.py", line 148, in get_converter
    converter = self.get_converter(xravel[0])
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/units.py", line 148, in get_converter
    converter = self.get_converter(xravel[0])
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/units.py", line 148, in get_converter
    converter = self.get_converter(xravel[0])
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/units.py", line 148, in get_converter
    converter = self.get_converter(xravel[0])
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/matplotlib/units.py", line 148, in get_converter
    converter = self.get_converter(xravel[0])
#keeps repeating line 148 error until
  File "/System/Library/Frameworks/Python.framework/Versions/2.7/Extras/lib/python/numpy/matrixlib/defmatrix.py", line 316, in __getitem__
    out = N.ndarray.__getitem__(self, index)
RuntimeError: maximum recursion depth exceeded

Cubic spline planning: Spline2D doesn't generate spline from closely spaced x-y waypoints

for example:
x-y waypoints which are closely spaced do not show a spline when run with main(), the Spline 2D test
x = [random.uniform(1, 1.05) for i in range(5)]
y = [random.uniform(1, 1.05) for i in range(5)]

while larger values do not show this as an issue
x = [random.uniform(1, 11.05) for i in range(5)]
y = [random.uniform(1, 11.05) for i in range(5)]

This would be useful for GPS lat long coordinates which have small absolute differences corresponding to reasonably large real life distances.
x = [37.3779926, 37.3778115, 37.3777806, 37.3779436]
y = [-122.0419519, -122.0420216, -122.0417949, -122.0417266]

Project Collaborations

Hello,

I'm working on dynamic astar planning and other planning algorithms. Would you be interested in accepting pull requests and possibly collaborating on future project development?

Fix spline depilated warning

.../PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py:48: DeprecationWarning: spline is deprecated!
spline is deprecated in scipy 0.19.0, use Bspline class instead.
kp = scipy.interpolate.spline(tk, kk, t, order=2)
/Users/atsushisakai/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/scipy/interpolate/interpolate.py:2889: DeprecationWarning: splmake is deprecated!
splmake is deprecated in scipy 0.19.0, use make_interp_spline instead.
return spleval(splmake(xk, yk, order=order, kind=kind, conds=conds), xnew)
/Users/atsushisakai/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/scipy/interpolate/interpolate.py:2889: DeprecationWarning: spleval is deprecated!
spleval is deprecated in scipy 0.19.0, use BSpline instead.
return spleval(splmake(xk, yk, order=order, kind=kind, conds=conds), xnew)
./PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py:73: DeprecationWarning: spline is deprecated!
spline is deprecated in scipy 0.19.0, use Bspline class instead.
kp = scipy.interpolate.spline(tk, kk, t, order=2)

difference between PythonRobotics and MATLABRobotics

Hi, I am reading probabilistic robotics this book, just find this repository, I have some questions:

  1. is there any difference between PythonRobotics and MATLABRobotics?
  2. all code corresponding to the <>
  3. any toturials?

path tracking

hi, regarding the lqr and mpc steering and speed control for path tracking : do you have any good papers, journals etc. as a reference for that implementation ?
kind regards

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!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.