Skip to content

Commit

Permalink
Fix library naming issue and test linking errors
Browse files Browse the repository at this point in the history
  • Loading branch information
naiveHobo committed May 7, 2020
1 parent 3f7cb54 commit d35aeee
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 57 deletions.
89 changes: 32 additions & 57 deletions nav2_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,83 +85,49 @@ set(dependencies
tf2_geometry_msgs
)

set(nav2_rviz_plugins_goal_headers_to_moc
set(nav2_rviz_plugins_headers_to_moc
include/nav2_rviz_plugins/ros_action_qevent.hpp
include/nav2_rviz_plugins/goal_pose_updater
include/nav2_rviz_plugins/goal_common
include/nav2_rviz_plugins/goal_tool.hpp
include/nav2_rviz_plugins/nav2_panel.hpp
include/nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
include/nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
)

add_library(nav2_rviz_plugins_goal SHARED
add_library(nav2_rviz_plugins SHARED
src/goal_tool.cpp
src/nav2_panel.cpp
${nav2_rviz_plugins_goal_headers_to_moc}
src/particle_cloud_display/flat_weighted_arrows_array.cpp
src/particle_cloud_display/particle_cloud_display.cpp
${nav2_rviz_plugins_headers_to_moc}
)

ament_target_dependencies(nav2_rviz_plugins_goal
ament_target_dependencies(nav2_rviz_plugins
${dependencies}
)

target_include_directories(nav2_rviz_plugins_goal PUBLIC
target_include_directories(nav2_rviz_plugins PUBLIC
${Qt5Widgets_INCLUDE_DIRS}
${OGRE_INCLUDE_DIRS}
)

target_link_libraries(nav2_rviz_plugins_goal
target_link_libraries(nav2_rviz_plugins
rviz_common::rviz_common
)


set(nav2_rviz_plugins_particle_cloud_display_headers_to_moc
include/nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
include/nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
)

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
# TODO: Make this specific to this project (not rviz default plugins)
target_compile_definitions(nav2_rviz_plugins_goal PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
target_compile_definitions(nav2_rviz_plugins PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
# prevent pluginlib from using boost
target_compile_definitions(nav2_rviz_plugins_goal PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")


add_library(nav2_rviz_plugins_particle_cloud_display SHARED
src/particle_cloud_display/flat_weighted_arrows_array.cpp
src/particle_cloud_display/particle_cloud_display.cpp
${nav2_rviz_plugins_particle_cloud_display_headers_to_moc}
)

ament_target_dependencies(nav2_rviz_plugins_particle_cloud_display
${dependencies}
)

target_include_directories(nav2_rviz_plugins_particle_cloud_display PUBLIC
${Qt5Widgets_INCLUDE_DIRS}
${OGRE_INCLUDE_DIRS}
)

target_link_libraries(nav2_rviz_plugins_particle_cloud_display
rviz_common::rviz_common
)

target_compile_definitions(nav2_rviz_plugins_particle_cloud_display PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
target_compile_definitions(nav2_rviz_plugins_particle_cloud_display PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
target_compile_definitions(nav2_rviz_plugins PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")

pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)

install(
TARGETS nav2_rviz_plugins_goal
EXPORT nav2_rviz_plugins_goal
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)

install(
TARGETS nav2_rviz_plugins_particle_cloud_display
EXPORT nav2_rviz_plugins_particle_cloud_display
TARGETS nav2_rviz_plugins
EXPORT nav2_rviz_plugins
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -183,8 +149,10 @@ if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rviz_visual_testing_framework REQUIRED)
find_package(rviz_common REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rviz_common REQUIRED)
find_package(rviz_default_plugins REQUIRED)

set(TEST_INCLUDE_DIRS
${OGRE_INCLUDE_DIRS}
Expand All @@ -193,13 +161,14 @@ if(BUILD_TESTING)
ament_include_directories_order(TEST_INCLUDE_DIRS ${TEST_INCLUDE_DIRS})

set(TEST_LINK_LIBRARIES
nav2_rviz_plugins_particle_cloud_display
nav2_rviz_plugins
)

set(TEST_TARGET_DEPENDENCIES
nav2_msgs
rviz_common
rclcpp
rviz_common
rviz_default_plugins
)

ament_add_gmock(particle_cloud_display_test
Expand Down Expand Up @@ -232,17 +201,23 @@ if(BUILD_TESTING)
endif()

ament_export_include_directories(include)
ament_export_interfaces(nav2_rviz_plugins_goal HAS_LIBRARY_TARGET)
ament_export_interfaces(nav2_rviz_plugins_particle_cloud_display HAS_LIBRARY_TARGET)
ament_export_interfaces(nav2_rviz_plugins HAS_LIBRARY_TARGET)
ament_export_dependencies(
Qt5
rviz_common
geometry_msgs
map_msgs
nav_msgs
nav2_util
nav2_msgs
nav_msgs
Qt5
rclcpp
rviz_common
rviz_default_plugins
rviz_ogre_vendor
rviz_rendering
std_msgs
tf2_geometry_msgs
visualization_msgs
pluginlib
rclcpp_lifecycle
)

ament_package()
4 changes: 4 additions & 0 deletions nav2_rviz_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,10 @@

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>nav2_msgs</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>rviz_common</test_depend>
<test_depend>rviz_default_plugins</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down

0 comments on commit d35aeee

Please sign in to comment.