Skip to content

Commit ab49aa4

Browse files
authored
[kilted] Update deprecated call to ament_target_dependencies (#215)
1 parent a55fc7c commit ab49aa4

File tree

3 files changed

+20
-18
lines changed

3 files changed

+20
-18
lines changed

imu_complementary_filter/CMakeLists.txt

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -24,14 +24,15 @@ target_compile_features(complementary_filter PUBLIC c_std_99 cxx_std_17) # Requ
2424
target_include_directories(complementary_filter PUBLIC
2525
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
2626
$<INSTALL_INTERFACE:include>)
27-
ament_target_dependencies(complementary_filter
28-
geometry_msgs
29-
message_filters
30-
rclcpp
31-
sensor_msgs
32-
std_msgs
33-
tf2
34-
tf2_ros
27+
target_link_libraries(complementary_filter PUBLIC
28+
${geometry_msgs_TARGETS}
29+
${sensor_msgs_TARGETS}
30+
${std_msgs_TARGETS}
31+
message_filters::message_filters
32+
rclcpp::rclcpp
33+
sensor_msgs::sensor_msgs_library
34+
tf2::tf2
35+
tf2_ros::tf2_ros
3536
)
3637
# Causes the visibility macros to use dllexport rather than dllimport,
3738
# which is appropriate when building the dll but not consuming it.

imu_filter_madgwick/CMakeLists.txt

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -22,14 +22,16 @@ target_compile_features(imu_filter_madgwick PUBLIC c_std_99 cxx_std_17) # Requi
2222
target_include_directories(imu_filter_madgwick PUBLIC
2323
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
2424
$<INSTALL_INTERFACE:include>)
25-
ament_target_dependencies(imu_filter_madgwick
26-
geometry_msgs
27-
rclcpp
28-
rclcpp_components
29-
sensor_msgs
30-
std_msgs
31-
tf2_geometry_msgs
32-
tf2_ros
25+
target_link_libraries(imu_filter_madgwick PUBLIC
26+
${geometry_msgs_TARGETS}
27+
${sensor_msgs_TARGETS}
28+
${std_msgs_TARGETS}
29+
rclcpp::rclcpp
30+
rclcpp_components::component
31+
rclcpp_components::component_manager
32+
sensor_msgs::sensor_msgs_library
33+
tf2_geometry_msgs::tf2_geometry_msgs
34+
tf2_ros::tf2_ros
3335
)
3436
rclcpp_components_register_nodes(imu_filter_madgwick "ImuFilterMadgwickRos")
3537
target_compile_definitions(imu_filter_madgwick

rviz_imu_plugin/CMakeLists.txt

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -61,9 +61,8 @@ add_library(${PROJECT_NAME} SHARED ${SRC_FILES})
6161
## the ``find_package(Qt4 ...)`` line above, or by the
6262
## ``set(QT_LIBRARIES Qt5::Widgets)``, and with whatever libraries
6363
## catkin has included.
64-
ament_target_dependencies(${PROJECT_NAME} PUBLIC ${dependencies})
6564

66-
target_link_libraries(${PROJECT_NAME} PUBLIC rviz_ogre_vendor::OgreMain rviz_ogre_vendor::OgreOverlay Qt5::Widgets)
65+
target_link_libraries(${PROJECT_NAME} PUBLIC rviz_ogre_vendor::OgreMain rviz_ogre_vendor::OgreOverlay Qt5::Widgets ${sensor_msgs_TARGETS} message_filters::message_filters rviz_common::rviz_common rviz_ogre_vendor::OgreMain rviz_rendering::rviz_rendering sensor_msgs::sensor_msgs_library tf2::tf2 tf2_ros::tf2_ros)
6766

6867
# prevent pluginlib from using boost
6968
target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")

0 commit comments

Comments
 (0)