Skip to content

Commit

Permalink
Switch nav2_smac_planner to modern CMake idioms. (#4634)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 20, 2024
1 parent 2e824e9 commit c2e4aab
Show file tree
Hide file tree
Showing 19 changed files with 224 additions and 211 deletions.
224 changes: 135 additions & 89 deletions nav2_smac_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,137 +4,168 @@ project(nav2_smac_planner)
set(CMAKE_BUILD_TYPE Release) #Debug, Release

find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(angles REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(std_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(pluginlib REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(angles REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(nlohmann_json REQUIRED)
find_package(ompl REQUIRED)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(visualization_msgs REQUIRED)

if(MSVC)
add_compile_definitions(_USE_MATH_DEFINES)
else()
add_compile_options(-O3 -Wextra -Wdeprecated -fPIC)
endif()

include_directories(
include
${OMPL_INCLUDE_DIRS}
)

set(library_name nav2_smac_planner)

set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
std_msgs
visualization_msgs
nav2_util
nav2_msgs
nav_msgs
geometry_msgs
builtin_interfaces
tf2_ros
nav2_costmap_2d
nav2_core
pluginlib
angles
eigen3_cmake_module
)

# Hybrid plugin
add_library(${library_name} SHARED
src/smac_planner_hybrid.cpp
# Common library
add_library(${library_name}_common SHARED
src/a_star.cpp
src/collision_checker.cpp
src/smoother.cpp
src/analytic_expansion.cpp
src/node_hybrid.cpp
src/node_lattice.cpp
src/collision_checker.cpp
src/costmap_downsampler.cpp
src/node_2d.cpp
src/node_basic.cpp
src/node_hybrid.cpp
src/node_lattice.cpp
src/smoother.cpp
)
target_include_directories(${library_name}_common
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${OMPL_INCLUDE_DIRS}
)
target_link_libraries(${library_name}_common PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::layers
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
nlohmann_json::nlohmann_json
${OMPL_LIBRARIES}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
${visualization_msgs_TARGETS}
)
target_link_libraries(${library_name}_common PRIVATE
angles::angles
)

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

ament_target_dependencies(${library_name}
${dependencies}
# Hybrid plugin
add_library(${library_name} SHARED
src/smac_planner_hybrid.cpp
)
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${OMPL_INCLUDE_DIRS}
)
target_link_libraries(${library_name} PUBLIC
${library_name}_common
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
nlohmann_json::nlohmann_json
${OMPL_LIBRARIES}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
${visualization_msgs_TARGETS}
)
target_link_libraries(${library_name} PRIVATE
pluginlib::pluginlib
)

# 2D plugin
add_library(${library_name}_2d SHARED
src/smac_planner_2d.cpp
src/a_star.cpp
src/smoother.cpp
src/collision_checker.cpp
src/analytic_expansion.cpp
src/node_hybrid.cpp
src/node_lattice.cpp
src/costmap_downsampler.cpp
src/node_2d.cpp
src/node_basic.cpp
)

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

ament_target_dependencies(${library_name}_2d
${dependencies}
target_include_directories(${library_name}_2d
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${OMPL_INCLUDE_DIRS}
)
target_link_libraries(${library_name}_2d PUBLIC
${library_name}_common
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
nlohmann_json::nlohmann_json
${OMPL_LIBRARIES}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
${visualization_msgs_TARGETS}
)
target_link_libraries(${library_name}_2d PRIVATE
pluginlib::pluginlib
)

# Lattice plugin
add_library(${library_name}_lattice SHARED
src/smac_planner_lattice.cpp
src/a_star.cpp
src/smoother.cpp
src/collision_checker.cpp
src/analytic_expansion.cpp
src/node_hybrid.cpp
src/node_lattice.cpp
src/costmap_downsampler.cpp
src/node_2d.cpp
src/node_basic.cpp
)

target_link_libraries(${library_name}_lattice ${OMPL_LIBRARIES})
target_include_directories(${library_name}_lattice PUBLIC ${Eigen3_INCLUDE_DIRS})

ament_target_dependencies(${library_name}_lattice
${dependencies}
target_include_directories(${library_name}_lattice
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${OMPL_INCLUDE_DIRS}
)
target_link_libraries(${library_name}_lattice PUBLIC
${library_name}_common
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
nlohmann_json::nlohmann_json
${OMPL_LIBRARIES}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
${visualization_msgs_TARGETS}
)
target_link_libraries(${library_name}_lattice PRIVATE
ament_index_cpp::ament_index_cpp
pluginlib::pluginlib
)

pluginlib_export_plugin_description_file(nav2_core smac_plugin_hybrid.xml)
pluginlib_export_plugin_description_file(nav2_core smac_plugin_2d.xml)
pluginlib_export_plugin_description_file(nav2_core smac_plugin_lattice.xml)

install(TARGETS ${library_name} ${library_name}_2d ${library_name}_lattice
install(TARGETS ${library_name}_common ${library_name} ${library_name}_2d ${library_name}_lattice
EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY include/
DESTINATION include/
DESTINATION include/${PROJECT_NAME}
)

install(DIRECTORY lattice_primitives/sample_primitives DESTINATION share/${PROJECT_NAME})
Expand All @@ -144,10 +175,25 @@ if(BUILD_TESTING)
set(AMENT_LINT_AUTO_FILE_EXCLUDE include/nav2_smac_planner/thirdparty/robin_hood.h)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_gtest REQUIRED)
ament_find_gtest()
add_subdirectory(test)
endif()

ament_export_include_directories(include ${OMPL_INCLUDE_DIRS})
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(${library_name} ${library_name}_2d ${library_name}_lattice)
ament_export_dependencies(${dependencies})
ament_export_dependencies(
geometry_msgs
nav2_core
nav2_costmap_2d
nav_msgs
nlohmann_json
ompl
rclcpp
rclcpp_lifecycle
rcl_interfaces
tf2
tf2_ros
visualization_msgs
)
ament_export_targets(${PROJECT_NAME})
ament_package()
8 changes: 3 additions & 5 deletions nav2_smac_planner/include/nav2_smac_planner/a_star.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,12 @@
#ifndef NAV2_SMAC_PLANNER__A_STAR_HPP_
#define NAV2_SMAC_PLANNER__A_STAR_HPP_

#include <vector>
#include <iostream>
#include <unordered_map>
#include <functional>
#include <memory>
#include <queue>
#include <utility>
#include <tuple>
#include "Eigen/Core"
#include <utility>
#include <vector>

#include "nav2_costmap_2d/costmap_2d.hpp"
#include "nav2_core/planner_exceptions.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@
#ifndef NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
#define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_

#include <string>
#include <vector>
#include <functional>
#include <list>
#include <memory>
#include <string>
#include <vector>

#include "nav2_smac_planner/node_2d.hpp"
#include "nav2_smac_planner/node_hybrid.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License. Reserved.

#include <vector>
#include <memory>
#include <vector>

#include "nav2_costmap_2d/footprint_collision_checker.hpp"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,8 @@
#ifndef NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
#define NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_

#include <algorithm>
#include <string>
#include <memory>
#include <string>

#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "nav2_smac_planner/constants.hpp"
Expand Down
10 changes: 3 additions & 7 deletions nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,10 @@
#ifndef NAV2_SMAC_PLANNER__NODE_2D_HPP_
#define NAV2_SMAC_PLANNER__NODE_2D_HPP_

#include <math.h>
#include <vector>
#include <iostream>
#include <memory>
#include <queue>
#include <limits>
#include <utility>
#include <functional>
#include <memory>
#include <stdexcept>
#include <vector>

#include "nav2_smac_planner/types.hpp"
#include "nav2_smac_planner/constants.hpp"
Expand Down
12 changes: 0 additions & 12 deletions nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,18 +15,6 @@
#ifndef NAV2_SMAC_PLANNER__NODE_BASIC_HPP_
#define NAV2_SMAC_PLANNER__NODE_BASIC_HPP_

#include <math.h>
#include <vector>
#include <cmath>
#include <iostream>
#include <functional>
#include <queue>
#include <memory>
#include <utility>
#include <limits>

#include "ompl/base/StateSpace.h"

#include "nav2_smac_planner/constants.hpp"
#include "nav2_smac_planner/node_hybrid.hpp"
#include "nav2_smac_planner/node_lattice.hpp"
Expand Down
7 changes: 1 addition & 6 deletions nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,10 @@
#ifndef NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
#define NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_

#include <math.h>
#include <vector>
#include <cmath>
#include <iostream>
#include <functional>
#include <queue>
#include <memory>
#include <utility>
#include <limits>
#include <vector>

#include "ompl/base/StateSpace.h"

Expand Down
Loading

0 comments on commit c2e4aab

Please sign in to comment.