diff --git a/nav2_voxel_grid/CMakeLists.txt b/nav2_voxel_grid/CMakeLists.txt index 4b88a87d86..afd87f59af 100644 --- a/nav2_voxel_grid/CMakeLists.txt +++ b/nav2_voxel_grid/CMakeLists.txt @@ -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 + "$" + "$") +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) @@ -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() diff --git a/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp b/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp index 07c391fff5..c537ff6cb7 100644 --- a/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp +++ b/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp @@ -44,7 +44,9 @@ #include #include #include -#include "rclcpp/rclcpp.hpp" + +#include +#include /** * @class VoxelGrid diff --git a/nav2_voxel_grid/src/voxel_grid.cpp b/nav2_voxel_grid/src/voxel_grid.cpp index 44a63e2e31..e4055448b3 100644 --- a/nav2_voxel_grid/src/voxel_grid.cpp +++ b/nav2_voxel_grid/src/voxel_grid.cpp @@ -36,6 +36,9 @@ *********************************************************************/ #include +#include +#include + namespace nav2_voxel_grid { VoxelGrid::VoxelGrid(unsigned int size_x, unsigned int size_y, unsigned int size_z)