Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Fix CMakeLists.txt
Browse files Browse the repository at this point in the history
naiveHobo committed May 7, 2020

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature. The key has expired.
1 parent 4500331 commit f5d7c13
Showing 1 changed file with 65 additions and 30 deletions.
95 changes: 65 additions & 30 deletions nav2_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -63,29 +63,10 @@ find_package(std_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)

set(nav2_rviz_plugins_headers_to_moc
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
)

include_directories(
include
)

set(library_name ${PROJECT_NAME})

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

set(dependencies
geometry_msgs
nav2_util
@@ -104,32 +85,83 @@ set(dependencies
tf2_geometry_msgs
)

ament_target_dependencies(${library_name}
set(nav2_rviz_plugins_goal_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
)

add_library(nav2_rviz_plugins_goal SHARED
src/goal_tool.cpp
src/nav2_panel.cpp
${nav2_rviz_plugins_goal_headers_to_moc}
)

ament_target_dependencies(nav2_rviz_plugins_goal
${dependencies}
)

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

target_link_libraries(${library_name}
target_link_libraries(nav2_rviz_plugins_goal
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(${library_name} PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")

target_compile_definitions(nav2_rviz_plugins_goal PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
# prevent pluginlib from using boost
target_compile_definitions(${library_name} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
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")

pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)

install(
TARGETS ${library_name}
EXPORT ${library_name}
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
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
@@ -151,7 +183,8 @@ 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_default_plugins REQUIRED)
find_package(rviz_common REQUIRED)
find_package(nav2_msgs REQUIRED)

set(TEST_INCLUDE_DIRS
${OGRE_INCLUDE_DIRS}
@@ -160,11 +193,12 @@ if(BUILD_TESTING)
ament_include_directories_order(TEST_INCLUDE_DIRS ${TEST_INCLUDE_DIRS})

set(TEST_LINK_LIBRARIES
${library_name}
nav2_rviz_plugins_particle_cloud_display
)

set(TEST_TARGET_DEPENDENCIES
nav2_msgs
rviz_common
rclcpp
)

@@ -198,7 +232,8 @@ if(BUILD_TESTING)
endif()

ament_export_include_directories(include)
ament_export_interfaces(${library_name} HAS_LIBRARY_TARGET)
ament_export_interfaces(nav2_rviz_plugins_goal HAS_LIBRARY_TARGET)
ament_export_interfaces(nav2_rviz_plugins_particle_cloud_display HAS_LIBRARY_TARGET)
ament_export_dependencies(
Qt5
rviz_common

0 comments on commit f5d7c13

Please sign in to comment.