Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Galactic sync 3 (July 13) #2449

Merged
merged 5 commits into from
Jul 13, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ bool BtActionServer<ActionT>::on_configure()
// use suffix '_rclcpp_node' to keep parameter file consistency #1773
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args",
"-r", std::string("__node:=") + node->get_name() + "_rclcpp_node",
"-r", std::string("__node:=") + std::string(node->get_name()) + action_name_ + "_rclcpp_node",
"--"});
// Support for handling the topic-based goal pose from rviz
client_node_ = std::make_shared<rclcpp::Node>("_", options);
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ BtNavigator::BtNavigator()
"nav2_is_battery_low_condition_bt_node",
"nav2_navigate_through_poses_action_bt_node",
"nav2_navigate_to_pose_action_bt_node",
"nav2_remove_passed_goals_action_bt_node"
"nav2_remove_passed_goals_action_bt_node",
"nav2_planner_selector_bt_node",
"nav2_controller_selector_bt_node",
"nav2_goal_checker_selector_bt_node"
Expand Down
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
Loading