Skip to content

Commit

Permalink
Add dependency for building on the buildfarm (#544)
Browse files Browse the repository at this point in the history
* Make rviz_default_plugins explicitly depend on Ogre.

The source code does directly include Ogre stuff, so it needs
to have this direct dependency.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Make rviz_default_plugins properly depend on resource_retriever.

That is, make sure to ament_export_dependencies() on it.
Also directly link resource_retriever::resource_retriever into
target_link_libraries.  In theory it should be enough to
put this in the TEST_TARGET_DEPENDENCIES, but that doesn't
work for some reason.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette authored May 7, 2020
1 parent daa3348 commit 3c84d62
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 1 deletion.
12 changes: 11 additions & 1 deletion rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,11 @@ target_include_directories(rviz_default_plugins PUBLIC
${TinyXML_INCLUDE_DIRS}
)

target_link_libraries(rviz_default_plugins PUBLIC
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay
)

# 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_default_plugins PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
Expand All @@ -236,6 +241,7 @@ target_compile_definitions(rviz_default_plugins PUBLIC "PLUGINLIB__DISABLE_BOOST
pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)

ament_target_dependencies(rviz_default_plugins
PUBLIC
geometry_msgs
interactive_markers
laser_geometry
Expand Down Expand Up @@ -263,6 +269,8 @@ ament_export_dependencies(
map_msgs
nav_msgs
rclcpp
resource_retriever
rviz_ogre_vendor
tf2
tf2_geometry_msgs
tf2_ros
Expand Down Expand Up @@ -585,7 +593,9 @@ if(BUILD_TESTING)
${SKIP_DISPLAY_TESTS})
if(TARGET robot_test)
target_include_directories(robot_test PUBLIC ${TEST_INCLUDE_DIRS})
target_link_libraries(robot_test ${TEST_LINK_LIBRARIES})
# TODO(clalancette): Figure out why putting resource_retriever in the
# TEST_TARGET_DEPENDENCIES doesn't work.
target_link_libraries(robot_test resource_retriever::resource_retriever ${TEST_LINK_LIBRARIES})
ament_target_dependencies(robot_test ${TEST_TARGET_DEPENDENCIES})
endif()

Expand Down
4 changes: 4 additions & 0 deletions rviz_default_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,15 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>qtbase5-dev</build_depend>
<build_depend>rviz_ogre_vendor</build_depend>

<build_export_depend>rviz_ogre_vendor</build_export_depend>

<exec_depend>libqt5-core</exec_depend>
<exec_depend>libqt5-gui</exec_depend>
<exec_depend>libqt5-opengl</exec_depend>
<exec_depend>libqt5-widgets</exec_depend>
<exec_depend>rviz_ogre_vendor</exec_depend>

<depend>geometry_msgs</depend>
<depend>interactive_markers</depend>
Expand Down

0 comments on commit 3c84d62

Please sign in to comment.