Skip to content

Commit

Permalink
Switch to target_link_libraries. (#1098)
Browse files Browse the repository at this point in the history
That way we can hide more libraries using PRIVATE.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Nov 23, 2023
1 parent 8691d3b commit e6475f3
Show file tree
Hide file tree
Showing 6 changed files with 45 additions and 45 deletions.
6 changes: 5 additions & 1 deletion rviz2/test/tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,11 @@ find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)

add_executable(send_lots_of_points_node send_lots_of_points_node.cpp)
ament_target_dependencies(send_lots_of_points_node rclcpp sensor_msgs geometry_msgs)
target_link_libraries(send_lots_of_points_node PRIVATE
${geometry_msgs_TARGETS}
rclcpp::rclcpp
${sensor_msgs_TARGETS}
)

get_filename_component(script_path "${PROJECT_SOURCE_DIR}/scripts/rviz1_to_rviz2.py" ABSOLUTE)
get_filename_component(config_path "${CMAKE_CURRENT_SOURCE_DIR}/configs" ABSOLUTE BASE_DIR)
Expand Down
48 changes: 22 additions & 26 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,13 +42,12 @@ find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tinyxml2_vendor REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(message_filters REQUIRED)
find_package(urdf REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)

find_package(TinyXML2 REQUIRED) # provided by tinyxml_vendor
find_package(TinyXML2 REQUIRED) # provided by tinyxml2_vendor

# Copy env_config.hpp so that env_config.cpp can find it
# TODO(jsquare): Get rid of copy hpp file
Expand Down Expand Up @@ -233,45 +232,43 @@ target_include_directories(rviz_common
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
)

target_link_libraries(rviz_common
PUBLIC
target_link_libraries(rviz_common PUBLIC
${geometry_msgs_TARGETS}
message_filters::message_filters
pluginlib::pluginlib
Qt5::Widgets
rclcpp::rclcpp
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay
Qt5::Widgets
rviz_rendering::rviz_rendering
${sensor_msgs_TARGETS}
${std_msgs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
yaml-cpp
)

ament_target_dependencies(rviz_common
PUBLIC
geometry_msgs
pluginlib
rclcpp
resource_retriever
rviz_rendering
sensor_msgs
std_msgs
tf2
tf2_geometry_msgs
tf2_ros
message_filters
tinyxml2_vendor
urdf
yaml_cpp_vendor
target_link_libraries(rviz_common PRIVATE
resource_retriever::resource_retriever
tinyxml2::tinyxml2
)

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(rviz_common PRIVATE "RVIZ_COMMON_BUILDING_LIBRARY")

ament_export_dependencies(
rviz_rendering
geometry_msgs
message_filters
pluginlib
Qt5
rclcpp
rviz_ogre_vendor
rviz_rendering
sensor_msgs
std_msgs
tf2
tf2_geometry_msgs
tf2_ros
urdf
yaml_cpp_vendor
)

Expand Down Expand Up @@ -442,8 +439,7 @@ if(BUILD_TESTING)
test/mock_property_change_receiver.cpp
${SKIP_DISPLAY_TESTS})
if(TARGET rviz_common_display_test)
target_link_libraries(rviz_common_display_test rviz_common Qt5::Widgets)
ament_target_dependencies(rviz_common_display_test yaml_cpp_vendor)
target_link_libraries(rviz_common_display_test rviz_common Qt5::Widgets yaml-cpp)
endif()
endif()

Expand Down
5 changes: 1 addition & 4 deletions rviz_common/include/rviz_common/yaml_config_reader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,7 @@
#include "rviz_common/config.hpp"
#include "rviz_common/visibility_control.hpp"

namespace YAML
{
class Node;
}
#include "yaml-cpp/yaml.h"

namespace rviz_common
{
Expand Down
1 change: 0 additions & 1 deletion rviz_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>message_filters</depend>
<depend>tinyxml2_vendor</depend>
Expand Down
2 changes: 2 additions & 0 deletions rviz_common/src/rviz_common/display_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
#ifndef RVIZ_COMMON__DISPLAY_FACTORY_HPP_
#define RVIZ_COMMON__DISPLAY_FACTORY_HPP_

#include <tinyxml2.h>

#include <string>

#include <QMap> // NOLINT: cpplint cannot handle include order here
Expand Down
28 changes: 15 additions & 13 deletions rviz_rendering/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,36 +98,38 @@ add_library(rviz_rendering SHARED
src/rviz_rendering/objects/wrench_visual.cpp
)

target_link_libraries(rviz_rendering
PUBLIC
target_link_libraries(rviz_rendering PUBLIC
Qt5::Widgets
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay
Qt5::Widgets
)
if(TARGET Eigen3::Eigen)
# TODO(sloretz) require target to exist when https://github.com/ros2/choco-packages/issues/19 is addressed
target_link_libraries(rviz_rendering PUBLIC Eigen3::Eigen)
else()
target_include_directories(rviz_rendering PUBLIC ${Eigen3_INCLUDE_DIRS})
endif()

target_link_libraries(rviz_rendering PRIVATE
ament_index_cpp::ament_index_cpp
assimp::assimp
resource_retriever::resource_retriever
)

target_include_directories(rviz_rendering
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
${Eigen3_INCLUDE_DIRS}
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(rviz_rendering PRIVATE "RVIZ_RENDERING_BUILDING_LIBRARY")

ament_target_dependencies(rviz_rendering
SYSTEM PUBLIC
rviz_assimp_vendor
)
ament_export_dependencies(
rviz_assimp_vendor
rviz_ogre_vendor
eigen3_cmake_module
Eigen3
resource_retriever
ament_index_cpp)
Qt5
rviz_ogre_vendor
)

# Export old-style CMake variables
ament_export_include_directories("include/${PROJECT_NAME}")
Expand Down

0 comments on commit e6475f3

Please sign in to comment.