File tree Expand file tree Collapse file tree 3 files changed +20
-18
lines changed Expand file tree Collapse file tree 3 files changed +20
-18
lines changed Original file line number Diff line number Diff line change @@ -24,14 +24,15 @@ target_compile_features(complementary_filter PUBLIC c_std_99 cxx_std_17) # Requ
24
24
target_include_directories (complementary_filter PUBLIC
25
25
$< BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>
26
26
$< 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
35
36
)
36
37
# Causes the visibility macros to use dllexport rather than dllimport,
37
38
# which is appropriate when building the dll but not consuming it.
Original file line number Diff line number Diff line change @@ -22,14 +22,16 @@ target_compile_features(imu_filter_madgwick PUBLIC c_std_99 cxx_std_17) # Requi
22
22
target_include_directories (imu_filter_madgwick PUBLIC
23
23
$< BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include>
24
24
$< 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
33
35
)
34
36
rclcpp_components_register_nodes (imu_filter_madgwick "ImuFilterMadgwickRos" )
35
37
target_compile_definitions (imu_filter_madgwick
Original file line number Diff line number Diff line change @@ -61,9 +61,8 @@ add_library(${PROJECT_NAME} SHARED ${SRC_FILES})
61
61
## the ``find_package(Qt4 ...)`` line above, or by the
62
62
## ``set(QT_LIBRARIES Qt5::Widgets)``, and with whatever libraries
63
63
## catkin has included.
64
- ament_target_dependencies (${PROJECT_NAME} PUBLIC ${dependencies} )
65
64
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 )
67
66
68
67
# prevent pluginlib from using boost
69
68
target_compile_definitions (${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS" )
You can’t perform that action at this time.
0 commit comments