Skip to content

Commit

Permalink
use modern cmake pluginlib (#542)
Browse files Browse the repository at this point in the history
* use modern cmake pluginlib

Signed-off-by: Knese Karsten <karsten@openrobotics.org>

* find pluginlib before geometry_msgs - magic

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* exported packages have to ordered as well

Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 authored May 20, 2020
1 parent 4b4be6e commit 7715057
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ find_package(rviz_ogre_vendor REQUIRED)

find_package(Qt5 REQUIRED COMPONENTS Widgets)

find_package(geometry_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(resource_retriever REQUIRED)
find_package(rviz_assimp_vendor REQUIRED)
Expand Down Expand Up @@ -235,15 +235,13 @@ target_include_directories(rviz_common
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${pluginlib_INCLUDE_DIRS}
${TinyXML_INCLUDE_DIRS}
)

target_link_libraries(rviz_common
PUBLIC
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay
${pluginlib_LIBRARIES}
rviz_rendering::rviz_rendering
Qt5::Widgets
${TinyXML_LIBRARIES}
Expand All @@ -252,6 +250,7 @@ target_link_libraries(rviz_common
ament_target_dependencies(rviz_common
PUBLIC
geometry_msgs
pluginlib
rclcpp
resource_retriever
rviz_assimp_vendor
Expand All @@ -273,8 +272,8 @@ target_compile_definitions(rviz_common PRIVATE "RVIZ_COMMON_BUILDING_LIBRARY")
ament_export_targets(rviz_common)
ament_export_dependencies(
rviz_rendering
geometry_msgs
pluginlib
geometry_msgs
rclcpp
sensor_msgs
std_msgs
Expand Down

0 comments on commit 7715057

Please sign in to comment.