Skip to content

Commit

Permalink
Switch nav2_voxel_grid to use modern CMake idioms. (#4556)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jul 24, 2024
1 parent d1ad640 commit f34ca63
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 12 deletions.
23 changes: 12 additions & 11 deletions nav2_voxel_grid/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,29 +7,26 @@ find_package(rclcpp REQUIRED)

nav2_package()

include_directories(
include)

add_library(voxel_grid SHARED
src/voxel_grid.cpp
)

set(dependencies
rclcpp
)

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

install(TARGETS voxel_grid
EXPORT voxel_grid
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

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

if(BUILD_TESTING)
Expand All @@ -39,11 +36,15 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)

ament_find_gtest()

add_subdirectory(test)
endif()

ament_export_dependencies(rclcpp)
ament_export_include_directories(include)
ament_export_libraries(voxel_grid)
ament_export_targets(voxel_grid)

ament_package()
4 changes: 3 additions & 1 deletion nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,9 @@
#include <math.h>
#include <limits.h>
#include <algorithm>
#include "rclcpp/rclcpp.hpp"

#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>

/**
* @class VoxelGrid
Expand Down
3 changes: 3 additions & 0 deletions nav2_voxel_grid/src/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@
*********************************************************************/
#include <nav2_voxel_grid/voxel_grid.hpp>

#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>

namespace nav2_voxel_grid
{
VoxelGrid::VoxelGrid(unsigned int size_x, unsigned int size_y, unsigned int size_z)
Expand Down

0 comments on commit f34ca63

Please sign in to comment.