Skip to content

Commit

Permalink
Various small CMake fixes.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Aug 23, 2024
1 parent 6bf9d68 commit 9d481fe
Show file tree
Hide file tree
Showing 8 changed files with 30 additions and 27 deletions.
8 changes: 4 additions & 4 deletions nav2_costmap_2d/test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -138,10 +138,10 @@ ament_add_test(test_costmap_subscriber_exec
# ament_add_gtest_executable(costmap_tester
# costmap_tester.cpp
# )
# ament_target_dependencies(costmap_tester
# ${dependencies}
# )
# target_link_libraries(costmap_tester
# nav2_costmap_2d_core
# layers
# nav2_costmap_2d::nav2_costmap_2d_core
# nav2_util::nav2_utils_core
# rclcpp::rclcpp
# tf2_ros::tf2_ros
# )
7 changes: 3 additions & 4 deletions nav2_dwb_controller/nav2_dwb_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
cmake_minimum_required(VERSION 3.5)
project(nav2_dwb_controller)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)

nav2_package()

ament_package()
15 changes: 8 additions & 7 deletions nav2_dwb_controller/nav2_dwb_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,15 @@
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<depend>costmap_queue</depend>
<depend>dwb_core</depend>
<depend>dwb_critics</depend>
<depend>dwb_msgs</depend>
<depend>dwb_plugins</depend>
<depend>nav_2d_msgs</depend>
<depend>nav_2d_utils</depend>
<exec_depend>costmap_queue</exec_depend>
<exec_depend>dwb_core</exec_depend>
<exec_depend>dwb_critics</exec_depend>
<exec_depend>dwb_msgs</exec_depend>
<exec_depend>dwb_plugins</exec_depend>
<exec_depend>nav_2d_msgs</exec_depend>
<exec_depend>nav_2d_utils</exec_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
15 changes: 9 additions & 6 deletions nav2_mppi_controller/benchmark/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,17 @@ foreach(name IN LISTS BENCHMARK_NAMES)
add_executable(${name}
${name}.cpp
)
ament_target_dependencies(${name}
${dependencies_pkgs}
)
target_link_libraries(${name}
mppi_controller mppi_critics benchmark
benchmark
${geometry_msgs_TARGETS}
mppi_controller
mppi_critics
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
)

target_include_directories(${name} PRIVATE
target_include_directories(${name} PRIVATE
${PROJECT_SOURCE_DIR}/test/utils
)
)
endforeach()
2 changes: 2 additions & 0 deletions nav2_mppi_controller/benchmark/optimizer_benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,9 @@
// limitations under the License.

#include <benchmark/benchmark.h>

#include <string>
#include <vector>

#include "gtest/gtest.h"
#include <geometry_msgs/msg/pose_stamped.hpp>
Expand Down
2 changes: 0 additions & 2 deletions nav2_smac_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 3.5)
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)
Expand Down
7 changes: 3 additions & 4 deletions navigation2/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
cmake_minimum_required(VERSION 3.5)
project(navigation2)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)

nav2_package()

ament_package()
1 change: 1 addition & 0 deletions navigation2/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<!-- nav2_bringup doesn't belong for recursive dependencies -->
<exec_depend>nav2_amcl</exec_depend>
Expand Down

0 comments on commit 9d481fe

Please sign in to comment.