Skip to content

Commit 7fa5509

Browse files
authored
Add lazy_theta_star (ros-navigation#1839)
* Add lazy_theta_star * Added license * Added license * Update lazy_theta_star_b.cpp * restructured files - separated planner part and the algorithm - implemented all the changes as suggested * restructured files * Update CMakeLists.txt * removed unnecessary comments * removed comments * Delete planner.cpp * Delete lazy_theta_star_b.cpp * Delete lazy_theta_star_b.h * Delete planner.h * Delete CMakeLists.txt * Delete global_planner_plugin.xml * Delete package.xml * replaced the files - refactored code - improved reliability - have to write a code similar to that in nav2_system_tests, to test it (working on it) * removed comments * removed comments * Update lazy_theta_star2.cpp * update files - replaced manual management of priority queue with stl priority queue - added the parameter ".lethal_cost" - removed unnecessary parameters passed to the functions * update files - updated the header files in accordance to their .cpp counterparts * Delete lazy_theta_star2.h * Delete lazy_theta_star_planner.h * Delete lazy_theta_star2.cpp * Delete lazy_theta_star_planner.cpp * Delete CMakeLists.txt * Delete package.xml * Delete global_planner_plugin.xml * upload the changed code Changes from last time are: - the code has been changed to the Lazy Theta* P variant, in order to account for the costmap traversal costs - parameters are available to change the weights of the costmap traversal cost (weight = 1.75, as of now) and the distance function (weight = 1.0, as of now - * Delete lazy_theta_star_p_planner directory * Replace the old files - the structure of code has been changed - new functions have been added, namely : getTraversalCost, getEuclideanCost, getCellCost, isSafe[it is now an overloaded function] - documentation added for variables and functions - the parameters for the planner now consists of : how_many_corners, costmap_tolerance, euc_tolerance (documentation to added soon) - fixed a bug where the incorrect traversal cost of the node was taken * Delete lazy_theta_star_p_planner directory * update the files - renamed the project to nav2_theta_star_planner from lazy_theta_star_p_planner - renamed files from lazy_theta_p_planner.hpp/.cpp to theta_star_planner.hpp/.cpp and lazy_theta_star.hpp/.cpp to theta_star.hpp/.cpp - added a readme file outlining the parameters, usage notes and images to be added soon - added parameters and renamed the parameters for the cost function (costmap_tolerance -> w_traversal_cost ; euc_tolerance -> w_euc_cost ; added a parameter for the heuristic) - replaced the SharedPtr with a WeakPtr for node - removed +1 and the pusher_ variable added to compensate for it * Update README.md * update the code - linted the code - **updates to readme, are still pending** - changed the type of message from INFO to DEBUG - replaced the capital letters with the smaller ones * update the readme file * Update README.md * Update README.md * Update README.md * Update README.md * Delete global_planner_plugin.xml * fix the linting issues * remove the space on line 7 * change RCLCPP_INFO to RCLCPP_DEBUG * Update README.md * Add test coverage - added tests to check the algorithm itself and its helper functions - added smoke test to detect plugin level issues - inlined some functions - shifted the functions `setStartAndGoal()` and `isSafeToPlan()` to the ThetaStar class - removed the functions `dist()` and `getCellCost()` from the ThetaStar class * update the test file * update the test file * Update README.md * Update README.md * Update README.md * add test on the size of the output path * Update README.md * Update README.md * change the function name from `isSafeToPlan()` to `isUnsafeToPlan()` * update the files - inlined the functions `getIndex` and `addIndex` - removed typos from the comments * fix typos * Update README.md * Update README.md * Update README.md * Update README.md * Update README.md * Update README.md * Update README.md * fix the typo - the first isSafe calls output wasn't negated, it has been fixed * Update theta_star.hpp - added the `getCost()` function (again) - replaced the use of indices with pointers to store the node's data, changes were made to the following functions - `addIndex()`, `getIndex()`, `initialisePosn()`. - the priority queue now stores the pointer to node's data and accordingly changes were made to `comp` struct - the global variable `curr_node` was renamed to `exp_node` - removed the struct `pos` * Update theta_star.cpp * update default parameters * update default parameters * Update README.md * update the test file * fix linting issues * Update README.md * Update README.md * Update README.md * Update theta_star_planner.cpp * update LETHAL_COST * update README.md * update dependency list * Update package.xml
1 parent ddfed98 commit 7fa5509

File tree

10 files changed

+1184
-0
lines changed

10 files changed

+1184
-0
lines changed
+81
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(nav2_theta_star_planner)
3+
4+
find_package(ament_cmake REQUIRED)
5+
find_package(builtin_interfaces REQUIRED)
6+
find_package(nav2_common REQUIRED)
7+
find_package(nav2_core REQUIRED)
8+
find_package(nav2_costmap_2d REQUIRED)
9+
find_package(nav2_msgs REQUIRED)
10+
find_package(nav2_util REQUIRED)
11+
find_package(pluginlib REQUIRED)
12+
find_package(rclcpp REQUIRED)
13+
find_package(rclcpp_action REQUIRED)
14+
find_package(rclcpp_lifecycle REQUIRED)
15+
find_package(tf2_ros REQUIRED)
16+
17+
nav2_package() #Calls the nav2_package.cmake file
18+
add_compile_options(-O3)
19+
20+
include_directories(
21+
include
22+
)
23+
24+
set(library_name ${PROJECT_NAME})
25+
26+
set(dependencies ament_cmake
27+
builtin_interfaces
28+
nav2_common
29+
nav2_core
30+
nav2_costmap_2d
31+
nav2_msgs
32+
nav2_util
33+
pluginlib
34+
rclcpp
35+
rclcpp_action
36+
rclcpp_lifecycle
37+
tf2_ros
38+
)
39+
40+
41+
add_library(${library_name} SHARED
42+
src/theta_star.cpp
43+
src/theta_star_planner.cpp
44+
)
45+
46+
ament_target_dependencies(${library_name} ${dependencies})
47+
48+
target_compile_definitions(${library_name} PUBLIC "PLUGINLIB_DISABLE_BOOST_FUNCTIONS")
49+
50+
pluginlib_export_plugin_description_file(nav2_core theta_star_planner.xml)
51+
52+
install(TARGETS ${library_name}
53+
ARCHIVE DESTINATION lib
54+
LIBRARY DESTINATION lib
55+
RUNTIME DESTINATION lib/${PROJECT_NAME}
56+
)
57+
58+
install(DIRECTORY include/
59+
DESTINATION include/
60+
)
61+
62+
install(FILES theta_star_planner.xml
63+
DESTINATION share/${PROJECT_NAME}
64+
)
65+
66+
67+
if(BUILD_TESTING)
68+
find_package(ament_lint_auto REQUIRED)
69+
set(gtest_disable_pthreads OFF)
70+
ament_lint_auto_find_test_dependencies()
71+
find_package(ament_cmake_gtest REQUIRED)
72+
ament_add_gtest(test_theta_star test/test_theta_star.cpp)
73+
ament_target_dependencies(test_theta_star ${dependencies})
74+
target_link_libraries(test_theta_star ${library_name})
75+
endif()
76+
77+
78+
ament_export_include_directories(include)
79+
ament_export_libraries(${library_name})
80+
ament_export_dependencies(${dependencies})
81+
ament_package()

nav2_theta_star_planner/README.md

+95
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,95 @@
1+
# Nav2 Theta Star Planner
2+
The Theta Star Planner is a global planning plugin meant to be used with the Nav2 Planner Server. The `nav2_theta_star_planner` implements a highly optimized version of the Theta\* Planner (specifically the [Lazy Theta\* P variant](http://idm-lab.org/bib/abstracts/papers/aaai10b.pdf)) meant to plan any-angle paths using A\*. The planner supports differential-drive and omni-directional robots.
3+
4+
## Features
5+
- The planner uses A\* search along with line of sight (LOS) checks to form any-angle paths thus avoiding zig-zag paths that may be present in the usual implementation of A\*
6+
- As it also considers the costmap traversal cost during execution it tends to smoothen the paths automatically, thus mitigating the need to smoothen the path (The presence of sharp turns depends on the resolution of the map, and it decreases as the map resolution increases)
7+
- Uses the costs from the costmap to penalise high cost regions
8+
- Allows to control the path behavior to either be any angle directed or to be in the middle of the spaces
9+
- Is well suited for smaller robots of the omni-directional and differential drive kind
10+
- The algorithmic part of the planner has been segregated from the plugin part to allow for reusability
11+
12+
## Metrics
13+
For the below example the planner took ~46ms (averaged value) to compute the path of 87.5m -
14+
![example.png](img/00-37.png)
15+
16+
The parameters were set to - `w_euc_cost: 1.0`, `w_traversal_cost: 5.0`, `w_heuristic_cost: 1.0` and the `global_costmap`'s `inflation_layer` parameters are set as - `cost_scaling_factor:5.0`, `inflation_radius: 5.5`
17+
18+
## Cost Function Details
19+
### Symbols and their meanings
20+
**g(a)** - cost function cost for the node 'a'
21+
22+
**h(a)** - heuristic function cost for the node 'a'
23+
24+
**f(a)** - total cost (g(a) + h(a)) for the node 'a'
25+
26+
**LETHAL_COST** - a value of the costmap traversal cost that inscribes an obstacle with
27+
respect to a function, value = 253
28+
29+
**curr** - represents the node whose neighbours are being added to the list
30+
31+
**neigh** - one of the neighboring nodes of curr
32+
33+
**par** - parent node of curr
34+
35+
**euc_cost(a,b)** - euclidean distance between the node type 'a' and type 'b'
36+
37+
**costmap_cost(a,b)** - the costmap traversal cost (ranges from 0 - 252, 254 = unknown value) between the node type 'a' and type 'b'
38+
39+
### Cost function
40+
```
41+
g(neigh) = g(curr) + w_euc_cost*euc_cost(curr, neigh) + w_traversal_cost*(costmap_cost(curr,neigh)/LETHAL_COST)^2
42+
h(neigh) = w_heuristic_cost * euc_cost(neigh, goal)
43+
f(neigh) = g(neigh) + h(neigh)
44+
```
45+
Because of how the program works when the 'neigh' init_rclcpp is to be expanded, depending
46+
on the result of the LOS check, (if the LOS check returns true) the value of g(neigh) might change to `g(par) +
47+
w1*euc_cost(par, neigh) + w2*(costmap(par,neigh)/LETHAL_COST)^2`
48+
49+
## Parameters
50+
The parameters of the planner are :
51+
- ` .how_many_corners ` : to choose between 4-connected and 8-connected graph expansions, the accepted values are 4 and 8
52+
- ` .w_euc_cost ` : weight applied on the length of the path.
53+
- ` .w_traversal_cost ` : it tunes how harshly the nodes of high cost are penalised. From the above g(neigh) equation you can see that the cost-aware component of the cost function forms a parabolic curve, thus this parameter would, on increasing its value, make that curve steeper allowing for a greater differentiation (as the delta of costs would increase, when the graph becomes steep) among the nodes of different costs.
54+
- ` .w_heuristic_cost ` : it has been provided to have an admissible heuristic
55+
56+
Below are the default values of the parameters :
57+
```
58+
planner_server:
59+
ros__parameters:
60+
planner_plugin_types: ["nav2_theta_star_planner/ThetaStarPlanner"]
61+
use_sim_time: True
62+
planner_plugin_ids: ["GridBased"]
63+
GridBased:
64+
how_many_corners: 8
65+
w_euc_cost: 1.0
66+
w_traversal_cost: 2.0
67+
w_heuristic_cost: 1.0
68+
```
69+
70+
## Usage Notes
71+
72+
### Tuning the Parameters
73+
Before starting off, do note that the costmap_cost(curr,neigh) component after being operated (ie before being multiplied to its parameter and being substituted in g(init_rclcpp)) varies from 0 to 1.
74+
75+
This planner uses the costs associated with each cell from the `global_costmap` as a measure of the point's proximity to the obstacles. Providing a gentle potential field that covers the entirety of the region (thus leading to only small pocket like regions of cost = 0) is recommended in order to achieve paths that pass through the middle of the spaces. A good starting point could be to set the `inflation_layer`'s parameters as - `cost_scaling_factor: 10.0`, `inflation_radius: 5.5` and then decrease the value of `cost_scaling_factor` to achieve the said potential field.
76+
77+
Providing a gentle potential field over the region allows the planner to exchange the increase in path lengths for a decrease in the accumulated traversal cost, thus leading to an increase in the distance from the obstacles. This around a corner allows for naturally smoothing the turns and removes the requirement for an external path smoother.
78+
79+
To begin with, you can set the parameters to its default values and then try increasing the value of `w_traversal_cost` to achieve those middling paths, but this would adversly make the paths less taut. So it is recommend ed that you simultaneously tune the value of `w_euc_cost`. Increasing `w_euc_cost` increases the tautness of the path, which leads to more straight line like paths (any-angled paths). Do note that the query time from the planner would increase for higher values of `w_traversal_cost` as more nodes would have to be expanded to lower the cost of the path, to counteract this you may also try setting `w_euc_cost` to a higher value and check if it reduces the query time.
80+
81+
Usually set `w_heuristic_cost` at the same value as `w_euc_cost` or 1.0 (whichever is lower). Though as a last resort you may increase the value of `w_heuristic_cost` to speed up the planning process, this is not recommended as it might not always lead to shorter query times, but would definitely give you sub optimal paths
82+
83+
Also note that changes to `w_traversal_cost` might cause slow downs, in case the number of node expanisions increase thus tuning it along with `w_euc_cost` is the way to go to.
84+
85+
While tuning the planner's parameters you can also change the `inflation_layer`'s parameters (of the global costmap) to tune the behavior of the paths.
86+
87+
### Path Smoothing
88+
Because of how the cost function works, the output path has a natural tendency to form smooth curves around corners, though the smoothness of the path depends on how wide the turn is, and the number of cells in that turn.
89+
90+
This planner is recommended to be used with local planners like DWB or TEB (or other any local planner / controllers that form a local trajectory to be traversed) as these take into account the abrupt turns which might arise due to the planner not being able to find a smoother turns owing to the aforementioned reasons.
91+
92+
While smoother paths can be achieved by increasing the costmap resolution (ie using a costmap of 1cm resolution rather than a 5cm one) it is not recommended to do so because it might increase the query times from the planner. Test the planners performance on the higher cm/px costmaps before making a switch to finer costmaps.
93+
94+
### Possible Applications
95+
This planner could be used in scenarios where planning speed matters over an extremely smooth path, which could anyways be handled by using a local planner/controller as mentioned above. Because of the any-angled nature of paths you can traverse environments diagonally (wherever it is allowed, eg: in a wide open region).

nav2_theta_star_planner/img/00-37.png

112 KB
Loading

0 commit comments

Comments
 (0)