Skip to content

Commit

Permalink
Switch nav2_costmap_2d to modern CMake idioms. (#4575)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jul 29, 2024
1 parent ca1fce1 commit e8852fc
Show file tree
Hide file tree
Showing 5 changed files with 137 additions and 127 deletions.
154 changes: 83 additions & 71 deletions nav2_costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,14 @@ cmake_minimum_required(VERSION 3.5)
project(nav2_costmap_2d)

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(laser_geometry REQUIRED)
find_package(map_msgs REQUIRED)
find_package(message_filters REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_util)
find_package(nav2_util REQUIRED)
find_package(nav2_voxel_grid REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(pluginlib REQUIRED)
Expand All @@ -18,15 +19,11 @@ find_package(rmw REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2_sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(angles REQUIRED)

remove_definitions(-DDISABLE_LIBUSB-1.0)
find_package(Eigen3 3.3 REQUIRED)

nav2_package()

Expand All @@ -44,41 +41,23 @@ add_library(nav2_costmap_2d_core SHARED
src/footprint_collision_checker.cpp
plugins/costmap_filters/costmap_filter.cpp
)
add_library(${PROJECT_NAME}::nav2_costmap_2d_core ALIAS nav2_costmap_2d_core)

target_include_directories(nav2_costmap_2d_core
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

set(dependencies
geometry_msgs
laser_geometry
map_msgs
message_filters
nav2_msgs
nav2_util
nav2_voxel_grid
nav_msgs
pluginlib
rclcpp
rclcpp_lifecycle
sensor_msgs
std_msgs
std_srvs
tf2
tf2_geometry_msgs
tf2_ros
tf2_sensor_msgs
visualization_msgs
angles
)

ament_target_dependencies(nav2_costmap_2d_core
${dependencies}
target_link_libraries(nav2_costmap_2d_core PUBLIC
${geometry_msgs_TARGETS}
${map_msgs_TARGETS}
${nav_msgs_TARGETS}
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
pluginlib::pluginlib
${std_srvs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
tf2_sensor_msgs::tf2_sensor_msgs
)
target_link_libraries(nav2_costmap_2d_core Eigen3::Eigen)

add_library(layers SHARED
plugins/inflation_layer.cpp
Expand All @@ -89,67 +68,79 @@ add_library(layers SHARED
plugins/range_sensor_layer.cpp
plugins/denoise_layer.cpp
)
add_library(${PROJECT_NAME}::layers ALIAS layers)
ament_target_dependencies(layers
${dependencies}
target_include_directories(layers
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(layers PUBLIC
angles::angles
rclcpp::rclcpp
message_filters::message_filters
laser_geometry::laser_geometry
nav2_voxel_grid::voxel_grid
nav2_costmap_2d_core
tf2::tf2
)
target_link_libraries(layers
${PROJECT_NAME}::nav2_costmap_2d_core
target_link_libraries(layers PRIVATE
pluginlib::pluginlib
)

add_library(filters SHARED
plugins/costmap_filters/keepout_filter.cpp
plugins/costmap_filters/speed_filter.cpp
plugins/costmap_filters/binary_filter.cpp
)
add_library(${PROJECT_NAME}::filters ALIAS filters)


ament_target_dependencies(filters
${dependencies}
target_include_directories(filters
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(filters
${PROJECT_NAME}::nav2_costmap_2d_core
target_link_libraries(filters PUBLIC
nav2_costmap_2d_core
${std_msgs_TARGETS}
tf2::tf2
)

add_library(nav2_costmap_2d_client SHARED
src/footprint_subscriber.cpp
src/costmap_subscriber.cpp
src/costmap_topic_collision_checker.cpp
)
add_library(${PROJECT_NAME}::nav2_costmap_2d_client ALIAS nav2_costmap_2d_client)

ament_target_dependencies(nav2_costmap_2d_client
${dependencies}
target_include_directories(nav2_costmap_2d_client
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

target_link_libraries(nav2_costmap_2d_client
${PROJECT_NAME}::nav2_costmap_2d_core
target_link_libraries(nav2_costmap_2d_client PUBLIC
nav2_costmap_2d_core
${std_msgs_TARGETS}
tf2::tf2
)

add_executable(nav2_costmap_2d_markers src/costmap_2d_markers.cpp)
target_link_libraries(nav2_costmap_2d_markers
${PROJECT_NAME}::nav2_costmap_2d_core
)

ament_target_dependencies(nav2_costmap_2d_markers
${dependencies}
target_link_libraries(nav2_costmap_2d_markers PRIVATE
${nav2_msgs_TARGETS}
nav2_voxel_grid::voxel_grid
nav2_util::nav2_util_core
rclcpp::rclcpp
${visualization_msgs_TARGETS}
)

add_executable(nav2_costmap_2d_cloud src/costmap_2d_cloud.cpp)
target_link_libraries(nav2_costmap_2d_cloud
${PROJECT_NAME}::nav2_costmap_2d_core
target_link_libraries(nav2_costmap_2d_cloud PRIVATE
nav2_voxel_grid::voxel_grid
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
${sensor_msgs_TARGETS}
${std_msgs_TARGETS}
)

add_executable(nav2_costmap_2d src/costmap_2d_node.cpp)
ament_target_dependencies(nav2_costmap_2d
${dependencies}
)

target_link_libraries(nav2_costmap_2d
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::layers
${PROJECT_NAME}::filters
target_link_libraries(nav2_costmap_2d PRIVATE
rclcpp::rclcpp
nav2_costmap_2d_core
)

install(TARGETS
Expand Down Expand Up @@ -183,11 +174,32 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
ament_find_gtest()
add_subdirectory(test)
pluginlib_export_plugin_description_file(nav2_costmap_2d test/regression/order_layer.xml)
endif()

ament_export_include_directories("include/${PROJECT_NAME}")
ament_export_libraries(layers filters nav2_costmap_2d_core nav2_costmap_2d_client)
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(${dependencies})
ament_export_dependencies(
angles
geometry_msgs
laser_geometry
map_msgs
message_filters
nav_msgs
nav2_msgs
nav2_util
nav2_voxel_grid
pluginlib
rclcpp
rmw
std_msgs
std_srvs
tf2
tf2_ros
tf2_sensor_msgs
)
pluginlib_export_plugin_description_file(nav2_costmap_2d costmap_plugins.xml)
ament_package()
5 changes: 3 additions & 2 deletions nav2_costmap_2d/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<depend>angles</depend>
<depend>geometry_msgs</depend>
<depend>laser_geometry</depend>
<depend>map_msgs</depend>
Expand All @@ -30,6 +31,7 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rmw</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
Expand All @@ -38,7 +40,6 @@
<depend>tf2_ros</depend>
<depend>tf2_sensor_msgs</depend>
<depend>visualization_msgs</depend>
<depend>angles</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand All @@ -49,6 +50,6 @@
<test_depend>nav2_lifecycle_manager</test_depend>

<export>
<build_type>ament_cmake</build_type>
<build_type>ament_cmake</build_type>
</export>
</package>
56 changes: 28 additions & 28 deletions nav2_costmap_2d/test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,65 +2,65 @@ ament_add_gtest_executable(footprint_tests_exec
footprint_tests.cpp
)
target_link_libraries(footprint_tests_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::layers
nav2_costmap_2d_core
layers
)

ament_add_gtest_executable(test_collision_checker_exec
test_costmap_topic_collision_checker.cpp
)
target_link_libraries(test_collision_checker_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::nav2_costmap_2d_client
${PROJECT_NAME}::layers
nav2_costmap_2d_core
nav2_costmap_2d_client
layers
)

ament_add_gtest_executable(inflation_tests_exec
inflation_tests.cpp
)
target_link_libraries(inflation_tests_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::layers
nav2_costmap_2d_core
layers
)

ament_add_gtest_executable(obstacle_tests_exec
obstacle_tests.cpp
)
target_link_libraries(obstacle_tests_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::layers
nav2_costmap_2d_core
layers
)

ament_add_gtest_executable(range_tests_exec
range_tests.cpp
)
target_link_libraries(range_tests_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::layers
nav2_costmap_2d_core
layers
)

ament_add_gtest(dyn_params_tests
dyn_params_tests.cpp
)
target_link_libraries(dyn_params_tests
${PROJECT_NAME}::nav2_costmap_2d_core
nav2_costmap_2d_core
)

ament_add_gtest_executable(test_costmap_publisher_exec
test_costmap_2d_publisher.cpp
test_costmap_2d_publisher.cpp
)
target_link_libraries(test_costmap_publisher_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::nav2_costmap_2d_client
${PROJECT_NAME}::layers
nav2_costmap_2d_core
nav2_costmap_2d_client
layers
)

ament_add_gtest_executable(test_costmap_subscriber_exec
test_costmap_subscriber.cpp
test_costmap_subscriber.cpp
)
target_link_libraries(test_costmap_subscriber_exec
${PROJECT_NAME}::nav2_costmap_2d_core
${PROJECT_NAME}::nav2_costmap_2d_client
nav2_costmap_2d_core
nav2_costmap_2d_client
)

ament_add_test(test_collision_checker
Expand Down Expand Up @@ -114,20 +114,20 @@ ament_add_test(range_tests
)

ament_add_test(test_costmap_publisher_exec
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
ENV
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
ENV
TEST_MAP=${TEST_MAP_DIR}/TenByTen.yaml
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:test_costmap_publisher_exec>
)

ament_add_test(test_costmap_subscriber_exec
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
ENV
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
ENV
TEST_MAP=${TEST_MAP_DIR}/TenByTen.yaml
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:test_costmap_subscriber_exec>
Expand All @@ -142,6 +142,6 @@ ament_add_test(test_costmap_subscriber_exec
# ${dependencies}
# )
# target_link_libraries(costmap_tester
# ${PROJECT_NAME}::nav2_costmap_2d_core
# nav2_costmap_2d_core
# layers
# )
Loading

0 comments on commit e8852fc

Please sign in to comment.