@@ -15,45 +15,36 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
15
15
add_compile_options (-Wall -Wextra -Wpedantic)
16
16
endif ()
17
17
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)
32
19
33
20
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)
45
29
46
30
## 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
52
32
src/wiimote_controller.cpp
53
33
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 )
57
48
58
49
rclcpp_components_register_node(
59
50
wiimote_lib
@@ -63,9 +54,19 @@ rclcpp_components_register_node(
63
54
## End C++ Wiimote Lib
64
55
65
56
# 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 )
69
70
70
71
rclcpp_components_register_node(
71
72
teleop_wiimote
@@ -80,11 +81,11 @@ if(BUILD_TESTING)
80
81
endif ()
81
82
82
83
# Install lib
83
- install (TARGETS wiimote_lib teleop_wiimote
84
+ install (TARGETS wiimote_lib teleop_wiimote EXPORT export_wiimote
84
85
ARCHIVE DESTINATION lib
85
86
LIBRARY DESTINATION lib
86
87
RUNTIME DESTINATION bin)
87
- install (DIRECTORY include / DESTINATION include )
88
+ install (DIRECTORY include / DESTINATION include / ${PROJECT_NAME} )
88
89
89
90
# Install launch and config files
90
91
install (DIRECTORY launch config
@@ -98,4 +99,15 @@ install(PROGRAMS nodes/feedback_tester.py
98
99
DESTINATION lib/${PROJECT_NAME}
99
100
)
100
101
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
+ )
0 commit comments