Skip to content

Commit 1b65aca

Browse files
authored
Revert "Fix dependency issues." (#259)
This reverts commit 11a70ca.
1 parent f06aece commit 1b65aca

File tree

3 files changed

+24
-23
lines changed

3 files changed

+24
-23
lines changed

joy/CMakeLists.txt

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
1010
add_compile_options(-Wall -Wextra -Wpedantic)
1111
endif()
1212

13-
find_package(ament_cmake REQUIRED)
13+
find_package(ament_cmake_ros REQUIRED)
1414
find_package(rclcpp REQUIRED)
1515
find_package(rclcpp_components REQUIRED)
1616
find_package(sdl2_vendor REQUIRED)
@@ -21,12 +21,12 @@ add_library(joy SHARED src/joy.cpp)
2121
target_include_directories(joy PUBLIC
2222
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
2323
"$<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}
2927
SDL2::SDL2)
28+
target_link_libraries(joy PRIVATE
29+
rclcpp_components::component)
3030

3131
install(TARGETS joy EXPORT export_joy
3232
LIBRARY DESTINATION lib

joy/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
<author>Blaise Gassend</author>
2323
<author>Jonathan Bohren</author>
2424

25-
<buildtool_depend>ament_cmake</buildtool_depend>
25+
<buildtool_depend>ament_cmake_ros</buildtool_depend>
2626

2727
<depend>rclcpp</depend>
2828
<depend>rclcpp_components</depend>

wiimote/CMakeLists.txt

Lines changed: 17 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -34,17 +34,17 @@ add_library(wiimote_lib SHARED
3434
target_include_directories(wiimote_lib PUBLIC
3535
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
3636
"$<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}
4644
wiimote::bluetooth
4745
wiimote::cwiid)
46+
target_link_libraries(wiimote_lib PRIVATE
47+
rclcpp_components::component)
4848

4949
rclcpp_components_register_node(
5050
wiimote_lib
@@ -59,13 +59,14 @@ add_library(teleop_wiimote SHARED
5959
target_include_directories(teleop_wiimote PUBLIC
6060
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
6161
"$<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)
6970

7071
rclcpp_components_register_node(
7172
teleop_wiimote

0 commit comments

Comments
 (0)