Skip to content

Commit

Permalink
Use target_link_libraries instead of ament_target_dependencies (#345)
Browse files Browse the repository at this point in the history
Signed-off-by: Shane Loretz <[email protected]>
  • Loading branch information
sloretz authored Feb 14, 2025
1 parent b021202 commit 22402b1
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 8 deletions.
6 changes: 3 additions & 3 deletions camera_calibration_parsers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,9 @@ ament_export_targets(export_${PROJECT_NAME})
#endif()
#add_library(${PROJECT_NAME}_wrapper
# src/parse_wrapper.cpp)
#ament_target_dependencies(${PROJECT_NAME}_wrapper
# "rclcpp"
# "sensor_msgs"
#target_link_libraries(${PROJECT_NAME}_wrapper
# rclcpp::rclcpp
# ${sensor_msgs_TARGETS}
#)
#target_include_directories(${PROJECT_NAME}_wrapper PUBLIC ${Boost_INCLUDE_DIRS} ${PYTHON_INCLUDE_DIRS})
#target_link_libraries(${PROJECT_NAME}_wrapper ${PROJECT_NAME} ${Boost_LIBRARIES} ${PYTHON_LIBRARIES} ${YAML_CPP_LIBRARIES})
Expand Down
8 changes: 3 additions & 5 deletions image_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,11 +65,9 @@ add_library(republish_node SHARED
)
target_link_libraries(republish_node
${PROJECT_NAME}
)
ament_target_dependencies(republish_node
pluginlib
rclcpp_components
rclcpp
pluginlib::pluginlib
rclcpp_components::component
rclcpp::rclcpp
)
rclcpp_components_register_node(republish_node
PLUGIN "image_transport::Republisher"
Expand Down

0 comments on commit 22402b1

Please sign in to comment.