Skip to content

Commit 6e67b78

Browse files
sloretzclalancette
andauthored
Install includes to include/ and misc CMake fixes (#225)
* Install includes to include/ and misc CMake fixes Make sure to really declare and find all dependencies. Co-authored-by: Chris Lalancette <[email protected]>
1 parent 6bb401d commit 6e67b78

File tree

5 files changed

+152
-70
lines changed

5 files changed

+152
-70
lines changed

joy/CMakeLists.txt

Lines changed: 17 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,18 +17,18 @@ find_package(sdl2_vendor REQUIRED)
1717
find_package(sdl2_custom REQUIRED)
1818
find_package(sensor_msgs REQUIRED)
1919

20-
include_directories(include)
2120
add_library(joy SHARED src/joy.cpp)
22-
ament_target_dependencies(joy
23-
"rclcpp_components"
24-
"rclcpp"
25-
"sensor_msgs")
26-
# Need this since sdl2 doesn't properly export its
27-
# libraries so ament_target_dependencies can find them
28-
target_link_libraries(joy
21+
target_include_directories(joy PUBLIC
22+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
23+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
24+
target_link_libraries(joy PUBLIC
25+
rclcpp::rclcpp
26+
${sensor_msgs_TARGETS}
2927
SDL2::SDL2)
28+
target_link_libraries(joy PRIVATE
29+
rclcpp_components::component)
3030

31-
install(TARGETS joy
31+
install(TARGETS joy EXPORT export_joy
3232
LIBRARY DESTINATION lib
3333
ARCHIVE DESTINATION lib
3434
RUNTIME DESTINATION bin
@@ -46,13 +46,18 @@ target_link_libraries(joy_enumerate_devices
4646
install(TARGETS joy_enumerate_devices
4747
DESTINATION lib/${PROJECT_NAME})
4848

49-
install(DIRECTORY include/${PROJECT_NAME}/
50-
DESTINATION include/${PROJECT_NAME}
51-
)
49+
install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
5250

5351
install(DIRECTORY config launch
5452
DESTINATION share/${PROJECT_NAME})
5553

54+
ament_export_targets(export_joy)
55+
ament_export_dependencies(
56+
"rclcpp"
57+
"sensor_msgs"
58+
"sdl2_vendor"
59+
"sdl2_custom")
60+
5661
if(BUILD_TESTING)
5762
find_package(ament_lint_auto REQUIRED)
5863
set(ament_cmake_copyright_FOUND TRUE)

spacenav/CMakeLists.txt

Lines changed: 28 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
cmake_minimum_required(VERSION 3.5)
2+
23
project(spacenav)
34

45
# Default to C++14
@@ -21,33 +22,41 @@ find_package(SPNAV REQUIRED)
2122
add_library(spacenav
2223
SHARED
2324
src/spacenav.cpp)
24-
target_include_directories(spacenav
25-
PUBLIC
26-
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
27-
$<INSTALL_INTERFACE:include>)
28-
ament_target_dependencies(spacenav
29-
"geometry_msgs"
30-
"rclcpp"
31-
"rclcpp_components"
32-
"sensor_msgs")
33-
34-
target_link_libraries(spacenav spnav)
25+
target_include_directories(spacenav PUBLIC
26+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
27+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
28+
${spnav_INCLUDE_DIR})
29+
target_link_libraries(spacenav PUBLIC
30+
rclcpp::rclcpp
31+
${geometry_msgs_TARGETS}
32+
${sensor_msgs_TARGETS}
33+
spnav)
34+
target_link_libraries(spacenav PRIVATE
35+
rclcpp_components::component)
3536

36-
# Install targets
37-
install(TARGETS spacenav
38-
ARCHIVE DESTINATION lib/${PROJECT_NAME}
39-
LIBRARY DESTINATION lib/${PROJECT_NAME}
40-
RUNTIME DESTINATION lib/${PROJECT_NAME}
37+
install(TARGETS spacenav EXPORT export_spacenav
38+
ARCHIVE DESTINATION lib
39+
LIBRARY DESTINATION lib
40+
RUNTIME DESTINATION bin
4141
)
4242

43+
rclcpp_components_register_node(spacenav
44+
PLUGIN "spacenav::Spacenav"
45+
EXECUTABLE spacenav_node)
46+
47+
install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
48+
4349
install(DIRECTORY
4450
launch
4551
DESTINATION share/${PROJECT_NAME}/
4652
)
4753

48-
rclcpp_components_register_node(spacenav
49-
PLUGIN "spacenav::Spacenav"
50-
EXECUTABLE spacenav_node)
54+
ament_export_targets(export_spacenav)
55+
ament_export_dependencies(
56+
"rclcpp"
57+
"geometry_msgs"
58+
"sensor_msgs"
59+
"spnav")
5160

5261
if(BUILD_TESTING)
5362
find_package(ament_lint_auto REQUIRED)

wiimote/CMakeLists.txt

Lines changed: 51 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -15,45 +15,36 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
1515
add_compile_options(-Wall -Wextra -Wpedantic)
1616
endif()
1717

18-
find_library(BLUETOOTH_LIB bluetooth)
19-
if(BLUETOOTH_LIB)
20-
message(STATUS "Found bluetooth library.")
21-
else()
22-
message(FATAL_ERROR "bluetooth library not found.")
23-
endif()
24-
25-
find_library(CWIID_LIB cwiid)
26-
if(CWIID_LIB)
27-
message(STATUS "Found cwiid library.")
28-
else()
29-
message(FATAL_ERROR "cwiid library not found.")
30-
endif()
31-
18+
include(wiimote-extras.cmake)
3219

3320
find_package(ament_cmake REQUIRED)
34-
find_package(ament_cmake_auto REQUIRED)
35-
36-
ament_auto_find_build_dependencies(
37-
REQUIRED
38-
rclcpp
39-
rclcpp_components
40-
rclcpp_lifecycle
41-
sensor_msgs
42-
std_srvs
43-
wiimote_msgs
44-
)
21+
find_package(geometry_msgs REQUIRED)
22+
find_package(rclcpp REQUIRED)
23+
find_package(rclcpp_components REQUIRED)
24+
find_package(rclcpp_lifecycle REQUIRED)
25+
find_package(sensor_msgs REQUIRED)
26+
find_package(std_msgs REQUIRED)
27+
find_package(std_srvs REQUIRED)
28+
find_package(wiimote_msgs REQUIRED)
4529

4630
## C++ Wiimote Lib
47-
set(wiimote_lib_HEADERS
48-
include/wiimote/wiimote_controller.hpp
49-
include/wiimote/stat_vector_3d.hpp)
50-
51-
set(wiimote_lib_SOURCES
31+
add_library(wiimote_lib SHARED
5232
src/wiimote_controller.cpp
5333
src/stat_vector_3d.cpp)
54-
55-
ament_auto_add_library(wiimote_lib SHARED ${wiimote_lib_HEADERS} ${wiimote_lib_SOURCES})
56-
target_link_libraries(wiimote_lib bluetooth cwiid)
34+
target_include_directories(wiimote_lib PUBLIC
35+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
36+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
37+
target_link_libraries(wiimote_lib PUBLIC
38+
rclcpp::rclcpp
39+
rclcpp_lifecycle::rclcpp_lifecycle
40+
${sensor_msgs_TARGETS}
41+
${std_msgs_TARGETS}
42+
${std_srvs_TARGETS}
43+
${wiimote_msgs_TARGETS}
44+
wiimote::bluetooth
45+
wiimote::cwiid)
46+
target_link_libraries(wiimote_lib PRIVATE
47+
rclcpp_components::component)
5748

5849
rclcpp_components_register_node(
5950
wiimote_lib
@@ -63,9 +54,19 @@ rclcpp_components_register_node(
6354
## End C++ Wiimote Lib
6455

6556
# C++ Teleop for Wiimote Node: Declare cpp executables
66-
set(teleop_wiimote_HEADERS include/wiimote/teleop_wiimote.hpp)
67-
set(teleop_wiimote_SOURCES src/teleop_wiimote.cpp)
68-
ament_auto_add_library(teleop_wiimote SHARED ${teleop_wiimote_HEADERS} ${teleop_wiimote_SOURCES})
57+
add_library(teleop_wiimote SHARED
58+
src/teleop_wiimote.cpp)
59+
target_include_directories(teleop_wiimote PUBLIC
60+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
61+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
62+
target_link_libraries(teleop_wiimote PUBLIC
63+
rclcpp::rclcpp
64+
rclcpp_lifecycle::rclcpp_lifecycle
65+
${geometry_msgs_TARGETS}
66+
${sensor_msgs_TARGETS}
67+
${wiimote_msgs_TARGETS})
68+
target_link_libraries(teleop_wiimote PRIVATE
69+
rclcpp_components::component)
6970

7071
rclcpp_components_register_node(
7172
teleop_wiimote
@@ -80,11 +81,11 @@ if(BUILD_TESTING)
8081
endif()
8182

8283
# Install lib
83-
install(TARGETS wiimote_lib teleop_wiimote
84+
install(TARGETS wiimote_lib teleop_wiimote EXPORT export_wiimote
8485
ARCHIVE DESTINATION lib
8586
LIBRARY DESTINATION lib
8687
RUNTIME DESTINATION bin)
87-
install(DIRECTORY include/ DESTINATION include)
88+
install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
8889

8990
# Install launch and config files
9091
install(DIRECTORY launch config
@@ -98,4 +99,15 @@ install(PROGRAMS nodes/feedback_tester.py
9899
DESTINATION lib/${PROJECT_NAME}
99100
)
100101

101-
ament_package()
102+
ament_export_targets(export_wiimote)
103+
ament_export_dependencies(
104+
"rclcpp"
105+
"sensor_msgs"
106+
"std_msgs"
107+
"std_srvs"
108+
"wiimote"
109+
)
110+
111+
ament_package(
112+
CONFIG_EXTRAS "wiimote-extras.cmake"
113+
)

wiimote/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,12 @@
3535
<build_depend>cwiid-dev</build_depend>
3636
<exec_depend>cwiid</exec_depend>
3737

38+
<depend>geometry_msgs</depend>
3839
<depend>rclcpp</depend>
3940
<depend>rclcpp_components</depend>
4041
<depend>rclcpp_lifecycle</depend>
4142
<depend>sensor_msgs</depend>
43+
<depend>std_msgs</depend>
4244
<depend>std_srvs</depend>
4345
<depend>wiimote_msgs</depend>
4446

wiimote/wiimote-extras.cmake

Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,54 @@
1+
# Copyright 2021 Intel Corporation
2+
# This program is free software: you can redistribute it and/or modify
3+
# it under the terms of the GNU General Public License as published by
4+
# the Free Software Foundation, either version 3 of the License, or
5+
# (at your option) any later version.
6+
#
7+
# This program is distributed in the hope that it will be useful,
8+
# but WITHOUT ANY WARRANTY; without even the implied warranty of
9+
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10+
# GNU General Public License for more details.
11+
#
12+
# You should have received a copy of the GNU General Public License
13+
# along with this program. If not, see <https://www.gnu.org/licenses/>.
14+
15+
find_library(BLUETOOTH_LIB bluetooth)
16+
if(BLUETOOTH_LIB)
17+
message(STATUS "Found bluetooth library.")
18+
else()
19+
message(FATAL_ERROR "bluetooth library not found.")
20+
endif()
21+
22+
find_path(BLUETOOTH_INCLUDE_DIR bluetooth/bluetooth.h)
23+
if(BLUETOOTH_LIB)
24+
message(STATUS "Found bluetooth header.")
25+
else()
26+
message(FATAL_ERROR "bluetooth header not found.")
27+
endif()
28+
29+
find_library(CWIID_LIB cwiid)
30+
if(CWIID_LIB)
31+
message(STATUS "Found cwiid library.")
32+
else()
33+
message(FATAL_ERROR "cwiid library not found.")
34+
endif()
35+
36+
find_path(CWIID_INCLUDE_DIR cwiid.h)
37+
if(CWIID_LIB)
38+
message(STATUS "Found cwiid header.")
39+
else()
40+
message(FATAL_ERROR "cwiid header not found.")
41+
endif()
42+
43+
add_library(wiimote::bluetooth INTERFACE IMPORTED)
44+
target_link_libraries(wiimote::bluetooth INTERFACE ${BLUETOOTH_LIB})
45+
target_include_directories(wiimote::bluetooth INTERFACE ${BLUETOOTH_INCLUDE_DIR})
46+
47+
add_library(wiimote::cwiid INTERFACE IMPORTED)
48+
target_link_libraries(wiimote::cwiid INTERFACE ${CWIID_LIB})
49+
target_include_directories(wiimote::cwiid INTERFACE ${CWIID_INCLUDE_DIR})
50+
51+
unset(BLUETOOTH_LIB)
52+
unset(BLUETOOTH_INCLUDE_DIR)
53+
unset(CWIID_LIB)
54+
unset(CWIID_INCLUDE_DIR)

0 commit comments

Comments
 (0)