Skip to content

Commit

Permalink
Use image_transport and cv_bridge targets (#62)
Browse files Browse the repository at this point in the history
* Use image_transport::image_transport target

Signed-off-by: Shane Loretz <[email protected]>

* Use cv_bridge::cv_bridge too

Signed-off-by: Shane Loretz <[email protected]>
  • Loading branch information
sloretz authored Jan 19, 2022
1 parent f7de1d4 commit 786a326
Showing 1 changed file with 2 additions and 4 deletions.
6 changes: 2 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,8 @@ set(rqt_image_view_INCLUDE_DIRECTORIES
${rclcpp_INCLUDE_DIRS}
${qt_gui_cpp_INCLUDE_DIRS}
${rqt_gui_cpp_INCLUDE_DIRS}
${image_transport_INCLUDE_DIRS}
${sensor_msgs_INCLUDE_DIRS}
${geometry_msgs_INCLUDE_DIRS}
${cv_bridge_INCLUDE_DIRS}
${Qt5Widgets_INCLUDE_DIRS}
)

Expand All @@ -77,10 +75,10 @@ target_link_libraries(
${rclcpp_LIBRARIES}
${qt_gui_cpp_LIBRARIES}
${rqt_gui_cpp_LIBRARIES}
${image_transport_LIBRARIES}
image_transport::image_transport
${sensor_msgs_LIBRARIES}
${geometry_msgs_LIBRARIES}
${cv_bridge_LIBRARIES}
cv_bridge::cv_bridge
Qt5::Widgets
)

Expand Down

0 comments on commit 786a326

Please sign in to comment.