File tree Expand file tree Collapse file tree 3 files changed +24
-23
lines changed Expand file tree Collapse file tree 3 files changed +24
-23
lines changed Original file line number Diff line number Diff line change @@ -10,7 +10,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10
10
add_compile_options (-Wall -Wextra -Wpedantic)
11
11
endif ()
12
12
13
- find_package (ament_cmake REQUIRED)
13
+ find_package (ament_cmake_ros REQUIRED)
14
14
find_package (rclcpp REQUIRED)
15
15
find_package (rclcpp_components REQUIRED)
16
16
find_package (sdl2_vendor REQUIRED)
@@ -21,12 +21,12 @@ add_library(joy SHARED src/joy.cpp)
21
21
target_include_directories (joy PUBLIC
22
22
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>"
23
23
"$<INSTALL_INTERFACE:include/${PROJECT_NAME} >" )
24
- ament_target_dependencies(joy
25
- rclcpp
26
- rclcpp_components
27
- sensor_msgs)
28
- target_link_libraries (joy
24
+ target_link_libraries (joy PUBLIC
25
+ rclcpp::rclcpp
26
+ ${sensor_msgs_TARGETS}
29
27
SDL2::SDL2)
28
+ target_link_libraries (joy PRIVATE
29
+ rclcpp_components::component )
30
30
31
31
install (TARGETS joy EXPORT export_joy
32
32
LIBRARY DESTINATION lib
Original file line number Diff line number Diff line change 22
22
<author >Blaise Gassend</author >
23
23
<author >Jonathan Bohren</author >
24
24
25
- <buildtool_depend >ament_cmake </buildtool_depend >
25
+ <buildtool_depend >ament_cmake_ros </buildtool_depend >
26
26
27
27
<depend >rclcpp</depend >
28
28
<depend >rclcpp_components</depend >
Original file line number Diff line number Diff line change @@ -34,17 +34,17 @@ add_library(wiimote_lib SHARED
34
34
target_include_directories (wiimote_lib PUBLIC
35
35
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>"
36
36
"$<INSTALL_INTERFACE:include/${PROJECT_NAME} >" )
37
- ament_target_dependencies(wiimote_lib
38
- rclcpp
39
- rclcpp_components
40
- rclcpp_lifecycle
41
- sensor_msgs
42
- std_msgs
43
- std_srvs
44
- wiimote_msgs)
45
- target_link_libraries (wiimote_lib
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}
46
44
wiimote::bluetooth
47
45
wiimote::cwiid)
46
+ target_link_libraries (wiimote_lib PRIVATE
47
+ rclcpp_components::component )
48
48
49
49
rclcpp_components_register_node(
50
50
wiimote_lib
@@ -59,13 +59,14 @@ add_library(teleop_wiimote SHARED
59
59
target_include_directories (teleop_wiimote PUBLIC
60
60
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>"
61
61
"$<INSTALL_INTERFACE:include/${PROJECT_NAME} >" )
62
- ament_target_dependencies(teleop_wiimote
63
- rclcpp
64
- rclcpp_components
65
- rclcpp_lifecycle
66
- geometry_msgs
67
- sensor_msgs
68
- wiimote_msgs)
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
You can’t perform that action at this time.
0 commit comments