Skip to content

Commit

Permalink
Switch costmap_queue to use modern CMake idioms.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Aug 8, 2024
1 parent 47a1235 commit fc58fbd
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 22 deletions.
46 changes: 26 additions & 20 deletions nav2_dwb_controller/costmap_queue/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,26 +4,20 @@ project(costmap_queue)
find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(rclcpp REQUIRED)

nav2_package()

include_directories(
include
)

add_library(${PROJECT_NAME} SHARED
src/costmap_queue.cpp
src/limited_costmap_queue.cpp
)

set(dependencies
rclcpp
nav2_costmap_2d
target_include_directories(${PROJECT_NAME}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

ament_target_dependencies(${PROJECT_NAME}
${dependencies}
target_link_libraries(${PROJECT_NAME} PUBLIC
nav2_costmap_2d::nav2_costmap_2d_core
)

if(BUILD_TESTING)
Expand All @@ -34,24 +28,36 @@ if(BUILD_TESTING)

find_package(ament_cmake_gtest REQUIRED)

find_package(rclcpp REQUIRED)

ament_find_gtest()

ament_add_gtest(mbq_test test/mbq_test.cpp)
ament_target_dependencies(mbq_test ${dependencies})
target_link_libraries(mbq_test
${PROJECT_NAME}
)

ament_add_gtest(utest test/utest.cpp)
ament_target_dependencies(utest ${dependencies})
target_link_libraries(utest ${PROJECT_NAME})
target_link_libraries(utest
${PROJECT_NAME}
nav2_costmap_2d::nav2_costmap_2d_core
rclcpp::rclcpp
)
endif()

install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
install(DIRECTORY include/
DESTINATION include/
DESTINATION include/${PROJECT_NAME}
)

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(${PROJECT_NAME})
ament_export_dependencies(nav2_costmap_2d)
ament_export_targets(${PROJECT_NAME})

ament_package()
4 changes: 2 additions & 2 deletions nav2_dwb_controller/costmap_queue/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@
<build_depend>nav2_common</build_depend>

<depend>nav2_costmap_2d</depend>
<depend>rclcpp</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>rclcpp</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down

0 comments on commit fc58fbd

Please sign in to comment.