Skip to content

Latest commit

 

History

History
55 lines (41 loc) · 2.9 KB

README.md

File metadata and controls

55 lines (41 loc) · 2.9 KB

Hybrid A* Path Planner for the KTH Research Concept Vehicle Build Status

The code in this repository is the result of my master's thesis which I am currently writing at the Integrated Research Lab (ITRL) at KTH Royal Institute of Technology. The code is documented here and the associated thesis can be found here.

The goal of the thesis and hence this code is to create a real-time path planning algorithm for the nonholonomic Research Concept Vehicle (RCV). The algorithm uses a binary obstacle map as an input, generated using LIDAR mounted on top of the vehicle. The algorithm is being developed using C++ due to real-time requirements in combination with ROS to ensure modularity and portability as well as using RViz as a visualization/simulation environment.

Key Characteristics
  • Sampling in continuous space with 72 different headings per cell (5° discretization)
  • Constrained Heuristic - nonholonomic without obstacles
  • Unconstrained Heuristic - holonomic with obstacles
  • Dubin's Shot
  • C++ real-time implementation (~10 Hz)

Large parts of the implementation are closely related to the hybrid A* algorithm developed by Dmitri Dolgov and Sebastian Thrun (Path Planning for Autonomous Vehicles in Unknown Semi-structured Environments DOI: 10.1177/0278364909359210)

Videos
Images

Reversing in a Maze

Parking

Mitigating a U-shape Obstacle

Dependencies

Setup

Run the following command to clone, build, and launch the package (requires a sources ROS environment):

sudo apt install libompl-dev \
&& mkdir -p ~/catkin_ws/src \
&& cd ~/catkin_ws/src \
&& git clone https://github.com/karlkurzer/path_planner.git  \
&& cd .. \
&& catkin_make \
&& source devel/setup.bash \
&& rospack profile \
&& roslaunch hybrid_astar manual.launch

Visualization (Rviz)

  1. Add -> By Topic -> /map, /path, /pathVehicle, (/visualizeNode2DPoses)
  2. Click 2D Pose Estimate to set a start point on the map
  3. Click 2D Nav Goal to set a goal point on the map
  4. Wait for the path being searched! (this process can be visualized [optional])