Skip to content

Latest commit

 

History

History
156 lines (126 loc) · 14.2 KB

README.md

File metadata and controls

156 lines (126 loc) · 14.2 KB

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.

This repository provides the implementations of common Motion planning algorithms. Your stars and forks are welcome. Maintaining this repository requires a huge amount of work. Therefore, you are also welcome to contribute to this repository by opening issues, submitting pull requests or joining our development team.

The theory analysis can be found at motion-planning.

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

Quick Start

The file structure is shown below

python_motion_planning
├─assets
├─docs
├─examples
└─python_motion_planning
    ├─global_planner
    |   ├─graph_search
    |   ├─sample_search
    |   └─evolutionary_search
    ├─local_planner
    ├─curve_generation
    └─utils
        ├─agent
        ├─environment
        ├─helper
        ├─planner
        └─plot
  • The global planning algorithm implementation is in the folder global_planner with graph_search, sample_search and evolutionary search.
  • The local planning algorithm implementation is in the folder local_planner.
  • The curve generation algorithm implementation is in the folder curve_generation.

The code was tested in python=3.10. To install other dependencies, please run the following command in shell.

pip install -r requirements.txt

To start simulation, open the folder example and select the algorithm, for example

if __name__ == '__main__':
    '''
    path searcher constructor
    '''
    search_factory = SearchFactory()
    
    '''
    graph search
    '''
    # build environment
    start = (5, 5)
    goal = (45, 25)
    env = Grid(51, 31)

    # creat planner
    planner = search_factory("a_star", start=start, goal=goal, env=env)
    # animation
    planner.run()

Version

Global Planner

Planner Version Animation
GBFS Status gbfs_python.png
Dijkstra Status dijkstra_python.png
A* Status a_star_python.png
JPS Status jps_python.png
D* Status d_star_python.png
LPA* Status lpa_star_python.png
D* Lite Status d_star_lite_python.png
Theta* Status theta_star_python.png
Lazy Theta* Status lazy_theta_star_python.png
S-Theta* Status s_theta_star_python.png
Anya Status Status
Voronoi Status voronoi_python.png
RRT Status rrt_python.png
RRT* Status rrt_star_python.png
Informed RRT Status informed_rrt_python.png
RRT-Connect Status rrt_connect_python.png
ACO Status aco_python.png
GA Status Status
PSO Status Status

Local Planner

Planner Version Animation
PID Status pid_python.svg
APF Status apf_python.svg
DWA Status dwa_python.svg
RPP Status rpp_python.svg
LQR Status lqr_python.svg
TEB Status Status
MPC Status mpc_python.svg
MPPI Status Status
Lattice Status Status
DDPG Status ddpg_python.svg

Curve Generation

Planner Version Animation
Polynomia Status polynomial_curve_python.gif
Bezier Status bezier_curve_python.png
Cubic Spline Status cubic_spline_python.png
BSpline Status bspline_curve_python.png
Dubins Status dubins_curve_python.png
Reeds-Shepp Status reeds_shepp_python.png
Fem-Pos Smoother Status fem_pos_smoother_python.png

Papers

Global Planning

  • A*: A Formal Basis for the heuristic Determination of Minimum Cost Paths
  • JPS: Online Graph Pruning for Pathfinding On Grid Maps
  • Lifelong Planning A*: Lifelong Planning A*
  • D*: Optimal and Efficient Path Planning for Partially-Known Environments
  • D* Lite: D* Lite
  • Theta*: Theta*: Any-Angle Path Planning on Grids
  • Lazy Theta*: Lazy Theta*: Any-Angle Path Planning and Path Length Analysis in 3D
  • S-Theta*: S-Theta*: low steering path-planning algorithm
  • Anya: Optimal Any-Angle Pathfinding In Practice
  • RRT: Rapidly-Exploring Random Trees: A New Tool for Path Planning
  • RRT-Connect: RRT-Connect: An Efficient Approach to Single-Query Path Planning
  • RRT*: Sampling-based algorithms for optimal motion planning
  • Informed RRT*: Optimal Sampling-based Path Planning Focused via Direct Sampling of an Admissible Ellipsoidal heuristic
  • ACO: Ant Colony Optimization: A New Meta-Heuristic

Local Planning

  • DWA: The Dynamic Window Approach to Collision Avoidance
  • APF: Real-time obstacle avoidance for manipulators and mobile robots
  • RPP: Regulated Pure Pursuit for Robot Path Tracking
  • DDPG: Continuous control with deep reinforcement learning

Curve Generation

  • Dubins: On curves of minimal length with a constraint on average curvature, and with prescribed initial and terminal positions and tangents

Acknowledgment