Skip to content

Commit

Permalink
Hybrid-A* optimizations and completion without on-going State Lattice…
Browse files Browse the repository at this point in the history
… work (#2404)

* major smac planner collision checking speedups and improvements

* fix linting errors

* wireframe for state lattice node

* finishing boilerplate changes

* adding more context to each TODO and notes about path to completion

* prototype for the base plugin + refactor out common logic for all planners

* commiting speed up work in progress

* adding in improvements to overall user quality of life

* pushing updates to 2D for faster / smoother; hybrid for smoother and new heuristic function; a bit of rearchitecture; deprecating smoother to make room for a new one

* adding smoother prototype

* adding orientation guestimator

* correcing 2d

* done with smoother

* enabling collision checking full SE2 only when under inscribed cost according to current exponential decay function

* adding doxgyen on new function

* linting

* testing working

* fixing looping at end of paths + simplifying code

* fixed cost-based issue in smoother

* finishing touches on smoothing

* smoother recursion fix + crashing issue resolved

* incremental changes

* completed hybrid A* plannern

* adding images

* purge state lattice work to merge in just Hybrid-A* improvements

* linting
  • Loading branch information
SteveMacenski committed Jun 18, 2021
1 parent 12fa591 commit 8a6607b
Show file tree
Hide file tree
Showing 43 changed files with 2,359 additions and 1,767 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,13 @@ class FootprintCollisionChecker
* @brief Set the current costmap object to use for collision detection
*/
void setCostmap(CostmapT costmap);
/**
* @brief Get the current costmap object
*/
CostmapT getCostmap()
{
return costmap_;
}

protected:
CostmapT costmap_;
Expand Down
45 changes: 28 additions & 17 deletions nav2_costmap_2d/src/footprint_collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,36 +51,40 @@ double FootprintCollisionChecker<CostmapT>::footprintCost(const Footprint footpr
unsigned int x0, x1, y0, y1;
double footprint_cost = 0.0;

// get the cell coord of the first point
if (!worldToMap(footprint[0].x, footprint[0].y, x0, y0)) {
return static_cast<double>(LETHAL_OBSTACLE);
}

// cache the start to eliminate a worldToMap call
unsigned int xstart = x0;
unsigned int ystart = y0;

// we need to rasterize each line in the footprint
for (unsigned int i = 0; i < footprint.size() - 1; ++i) {
// get the cell coord of the first point
if (!worldToMap(footprint[i].x, footprint[i].y, x0, y0)) {
return static_cast<double>(LETHAL_OBSTACLE);
}

// get the cell coord of the second point
if (!worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1)) {
return static_cast<double>(LETHAL_OBSTACLE);
}

footprint_cost = std::max(lineCost(x0, x1, y0, y1), footprint_cost);
}

// we also need to connect the first point in the footprint to the last point
// get the cell coord of the last point
if (!worldToMap(footprint.back().x, footprint.back().y, x0, y0)) {
return static_cast<double>(LETHAL_OBSTACLE);
}
// the second point is next iteration's first point
x0 = x1;
y0 = y1;

// get the cell coord of the first point
if (!worldToMap(footprint.front().x, footprint.front().y, x1, y1)) {
return static_cast<double>(LETHAL_OBSTACLE);
// if in collision, no need to continue
if (footprint_cost == static_cast<double>(INSCRIBED_INFLATED_OBSTACLE) ||
footprint_cost == static_cast<double>(LETHAL_OBSTACLE))
{
return footprint_cost;
}
}

footprint_cost = std::max(lineCost(x0, x1, y0, y1), footprint_cost);

// if all line costs are legal... then we can return that the footprint is legal
return footprint_cost;
// we also need to connect the first point in the footprint to the last point
// the last iteration's x1, y1 are the last footprint point's coordinates
return std::max(lineCost(xstart, x1, ystart, y1), footprint_cost);
}

template<typename CostmapT>
Expand All @@ -95,6 +99,13 @@ double FootprintCollisionChecker<CostmapT>::lineCost(int x0, int x1, int y0, int
if (line_cost < point_cost) {
line_cost = point_cost;
}

// if in collision, no need to continue
if (line_cost == static_cast<double>(INSCRIBED_INFLATED_OBSTACLE) ||
line_cost == static_cast<double>(LETHAL_OBSTACLE))
{
return line_cost;
}
}

return line_cost;
Expand Down
23 changes: 13 additions & 10 deletions nav2_smac_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ find_package(builtin_interfaces REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(pluginlib REQUIRED)
find_package(Ceres REQUIRED COMPONENTS SuiteSparse)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(ompl REQUIRED)
Expand All @@ -35,12 +34,16 @@ add_compile_options(-O3 -Wextra -Wdeprecated -fPIC)

include_directories(
include
${CERES_INCLUDES}
${OMPL_INCLUDE_DIRS}
${OpenMP_INCLUDE_DIRS}
)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")

find_package(OpenMP)
if(OPENMP_FOUND)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
endif()

set(library_name nav2_smac_planner)

Expand All @@ -62,16 +65,16 @@ set(dependencies
eigen3_cmake_module
)

# SE2 plugin
# Hybrid plugin
add_library(${library_name} SHARED
src/smac_planner.cpp
src/smac_planner_hybrid.cpp
src/a_star.cpp
src/node_se2.cpp
src/node_hybrid.cpp
src/costmap_downsampler.cpp
src/node_2d.cpp
)

target_link_libraries(${library_name} ${CERES_LIBRARIES} ${OMPL_LIBRARIES} ${OpenMP_LIBRARIES} OpenMP::OpenMP_CXX)
target_link_libraries(${library_name} ${OMPL_LIBRARIES} ${OpenMP_LIBRARIES} OpenMP::OpenMP_CXX)
target_include_directories(${library_name} PUBLIC ${Eigen3_INCLUDE_DIRS})

ament_target_dependencies(${library_name}
Expand All @@ -82,12 +85,12 @@ ament_target_dependencies(${library_name}
add_library(${library_name}_2d SHARED
src/smac_planner_2d.cpp
src/a_star.cpp
src/node_se2.cpp
src/node_hybrid.cpp
src/costmap_downsampler.cpp
src/node_2d.cpp
)

target_link_libraries(${library_name}_2d ${CERES_LIBRARIES} ${OMPL_LIBRARIES})
target_link_libraries(${library_name}_2d ${OMPL_LIBRARIES})
target_include_directories(${library_name}_2d PUBLIC ${Eigen3_INCLUDE_DIRS})

ament_target_dependencies(${library_name}_2d
Expand Down

0 comments on commit 8a6607b

Please sign in to comment.