Skip to content

Commit

Permalink
More cleanups to the cmake files and packages.
Browse files Browse the repository at this point in the history
Make sure to really declare and find all dependencies.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Jan 28, 2022
1 parent e4ff192 commit 0d2b8e5
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 10 deletions.
26 changes: 18 additions & 8 deletions spacenav/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
cmake_minimum_required(VERSION 3.5)

project(spacenav)

# Default to C++14
Expand All @@ -23,6 +24,7 @@ add_library(spacenav
src/spacenav.cpp)
target_include_directories(spacenav PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${spnav_INCLUDE_DIR})
target_link_libraries(spacenav PUBLIC
rclcpp::rclcpp
Expand All @@ -32,21 +34,29 @@ target_link_libraries(spacenav PUBLIC
target_link_libraries(spacenav PRIVATE
rclcpp_components::component)

# Install targets
install(TARGETS spacenav
ARCHIVE DESTINATION lib/${PROJECT_NAME}
LIBRARY DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION lib/${PROJECT_NAME}
install(TARGETS spacenav EXPORT export_spacenav
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

rclcpp_components_register_node(spacenav
PLUGIN "spacenav::Spacenav"
EXECUTABLE spacenav_node)

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

install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}/
)

rclcpp_components_register_node(spacenav
PLUGIN "spacenav::Spacenav"
EXECUTABLE spacenav_node)
ament_export_targets(export_spacenav)
ament_export_dependencies(
"rclcpp"
"geometry_msgs"
"sensor_msgs"
"spnav")

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
11 changes: 9 additions & 2 deletions wiimote/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ endif()
include(wiimote-extras.cmake)

find_package(ament_cmake REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
Expand All @@ -39,7 +40,6 @@ target_link_libraries(wiimote_lib PUBLIC
${sensor_msgs_TARGETS}
${std_msgs_TARGETS}
${std_srvs_TARGETS}
${geometry_msgs_TARGETS}
${wiimote_msgs_TARGETS}
wiimote::bluetooth
wiimote::cwiid)
Expand All @@ -62,8 +62,8 @@ target_include_directories(teleop_wiimote PUBLIC
target_link_libraries(teleop_wiimote PUBLIC
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${sensor_msgs_TARGETS}
${geometry_msgs_TARGETS}
${sensor_msgs_TARGETS}
${wiimote_msgs_TARGETS})
target_link_libraries(teleop_wiimote PRIVATE
rclcpp_components::component)
Expand Down Expand Up @@ -100,6 +100,13 @@ install(PROGRAMS nodes/feedback_tester.py
)

ament_export_targets(export_wiimote)
ament_export_dependencies(
"rclcpp"
"sensor_msgs"
"std_msgs"
"std_srvs"
"wiimote"
)

ament_package(
CONFIG_EXTRAS "wiimote-extras.cmake"
Expand Down
2 changes: 2 additions & 0 deletions wiimote/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,12 @@
<build_depend>cwiid-dev</build_depend>
<exec_depend>cwiid</exec_depend>

<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>wiimote_msgs</depend>

Expand Down

0 comments on commit 0d2b8e5

Please sign in to comment.