Skip to content

Commit 57ea01f

Browse files
committed
Fix targets
1 parent 735dca6 commit 57ea01f

File tree

1 file changed

+7
-6
lines changed

1 file changed

+7
-6
lines changed

zbar_ros/CMakeLists.txt

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,14 @@ include_directories(
2929
# Build library
3030
add_library(barcode_reader_node src/barcode_reader_node.cpp)
3131
target_link_libraries(barcode_reader_node PUBLIC
32-
rclcpp
33-
sensor_msgs
34-
std_msgs
35-
cv_bridge
36-
zbar_ros_interfaces
32+
${sensor_msgs_TARGETS}
33+
${std_msgs_TARGETS}
34+
${zbar_ros_interfaces_TARGETS}
35+
cv_bridge::cv_bridge
36+
rclcpp::rclcpp
37+
sensor_msgs::sensor_msgs_library
38+
zbar
3739
)
38-
target_link_libraries(barcode_reader_node zbar)
3940

4041
# Build executable
4142
add_executable(barcode_reader src/barcode_reader_main.cpp)

0 commit comments

Comments
 (0)