Skip to content

Motion planning(Path Planning and Trajectory Planning/Tracking) of AGV/AMR:python implementation of Dijkstra, A*, JPS, D*, LPA*, D* Lite, (Lazy)Theta*, RRT, RRT*, RRT-Connect, Informed RRT*, Voronoi, PID, DWA, APF, LQR, MPC, RPP, Bezier, Dubins etc.

License

Notifications You must be signed in to change notification settings

ai-winter/python_motion_planning

Repository files navigation

Introduction

Motion planning plans the state sequence of the robot without conflict between the start and goal.

Motion planning mainly includes Path planning and Trajectory planning.

  • Path Planning: It's based on path constraints (such as obstacles), planning the optimal path sequence for the robot to travel without conflict between the start and goal.
  • Trajectory planning: It plans the motion state to approach the global path based on kinematics, dynamics constraints and path sequence.

The theory analysis can be found at motion-planning.

We also provide ROS C++ version and Matlab version.

This repository provides the implementations of common Motion planning algorithms. Your stars and forks are welcome. Submitting pull requests or joining our development team are also welcome. For trivial modification, please directly contribute to dev branch. For big modification, please contact us before you contribute.

Quick Start

Overview

The source file structure is shown below

python_motion_planning
├─common
|   ├─env
|   |   ├─map
|   |   ├─robot
|   |   └─world
|   ├─utils
|   └─visualizer
├─controller
|   └─path_tracker
├─path_planner
|   ├─graph_search
|   └─sample_search
└─curve_generation

Install

(Optional) The code was tested in python=3.10, though other similar versions should also work. We recommend using conda to install the dependencies.

conda create -n pmp python=3.10
conda activate pmp

To install the repository, please run the following command in shell.

pip install python-motion-planning==2.0.dev1

Run

Please refer to the Tutorials part of online documentation.

Demos

Path Planner

Planner 2D Grid 3D Grid
GBFS Implemented in V1.1.1, not migrated Not implemented
Dijkstra dijkstra_2d.svg dijkstra_3d.svg
A* a_star_2d.svg a_star_3d.svg
JPS Implemented in V1.1.1, not migrated Not implemented
D* Implemented in V1.1.1, not migrated Not implemented
LPA* Implemented in V1.1.1, not migrated Not implemented
D* Lite Implemented in V1.1.1, not migrated Not implemented
Theta* theta_star_2d.svg theta_star_3d.svg
Lazy Theta* Implemented in V1.1.1, not migrated Not implemented
S-Theta* Implemented in V1.1.1, not migrated Not implemented
Anya Not implemented Not implemented
Voronoi Implemented in V1.1.1, not migrated Not implemented
RRT rrt_2d.svg rrt_3d.svg
RRT* rrt_star_2d.svg rrt_star_3d.svg
Informed RRT Implemented in V1.1.1, not migrated Not implemented
RRT-Connect Implemented in V1.1.1, not migrated Not implemented
ACO Implemented in V1.1.1, not migrated Not implemented
GA Implemented in V1.1.1, not migrated Not implemented
PSO Implemented in V1.1.1, not migrated Not implemented

Controller

We provide a toy simulator with simple physical simulation to test controllers (path-trakcers). The toy simulator supports multi-agents/multi-robots. The available robots include CircularRobot (Omnidirectional) and DiffDriveRobot (Only support moving forward and backward). Currently only 2D simulator is provided. 3D simulator has not been implemented.

In the following demos, the blue robot 1 is the CircularRobot, and the orange robot 2 is the DiffDriveRobot.

Planner 2D 3D
Path Trakcer path_tracker_2d.gif Not implemented
Pure Pursuit pure_pursuit_2d.gif Not implemented
PID pid_2d.gif Not implemented
APF apf_2d.gif Not implemented
DWA dwa_2d.gif Not implemented
RPP Implemented in V1.1.1, not migrated Not implemented
LQR Implemented in V1.1.1, not migrated Not implemented
MPC Implemented in V1.1.1, not migrated Not implemented
MPPI Not implemented Not implemented
TEB Not implemented Not implemented
Lattice Not implemented Not implemented
DQN Not implemented Not implemented
DDPG Implemented in V1.0, not migrated Not implemented

Curve Generator

The visualization of the curve generators has not been implemented in current version. They can be visualized in V1.1.1.

Planner 2D 3D
Polynomia polynomial_curve_python.gif Not implemented
Bezier bezier_curve_python.png Not implemented
Cubic Spline cubic_spline_python.png Not implemented
BSpline bspline_curve_python.png Not implemented
Dubins dubins_curve_python.png Not implemented
Reeds-Shepp reeds_shepp_python.png Not implemented
Fem-Pos Smoother fem_pos_smoother_python.png Not implemented

Contact

Long-term maintainers:

You can contact us via the information provided on our profile.