Skip to content

Commit dbc3503

Browse files
committed
Fix library naming issue and test linking errors
1 parent 3f7cb54 commit dbc3503

File tree

1 file changed

+54
-57
lines changed

1 file changed

+54
-57
lines changed

nav2_rviz_plugins/CMakeLists.txt

Lines changed: 54 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -85,83 +85,49 @@ set(dependencies
8585
tf2_geometry_msgs
8686
)
8787

88-
set(nav2_rviz_plugins_goal_headers_to_moc
88+
set(nav2_rviz_plugins_headers_to_moc
8989
include/nav2_rviz_plugins/ros_action_qevent.hpp
9090
include/nav2_rviz_plugins/goal_pose_updater
9191
include/nav2_rviz_plugins/goal_common
9292
include/nav2_rviz_plugins/goal_tool.hpp
9393
include/nav2_rviz_plugins/nav2_panel.hpp
94+
include/nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
95+
include/nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
9496
)
9597

96-
add_library(nav2_rviz_plugins_goal SHARED
98+
add_library(nav2_rviz_plugins SHARED
9799
src/goal_tool.cpp
98100
src/nav2_panel.cpp
99-
${nav2_rviz_plugins_goal_headers_to_moc}
101+
src/particle_cloud_display/flat_weighted_arrows_array.cpp
102+
src/particle_cloud_display/particle_cloud_display.cpp
103+
${nav2_rviz_plugins_headers_to_moc}
100104
)
101105

102-
ament_target_dependencies(nav2_rviz_plugins_goal
106+
ament_target_dependencies(nav2_rviz_plugins
103107
${dependencies}
104108
)
105109

106-
target_include_directories(nav2_rviz_plugins_goal PUBLIC
110+
target_include_directories(nav2_rviz_plugins PUBLIC
107111
${Qt5Widgets_INCLUDE_DIRS}
108112
${OGRE_INCLUDE_DIRS}
109113
)
110114

111-
target_link_libraries(nav2_rviz_plugins_goal
115+
target_link_libraries(nav2_rviz_plugins
112116
rviz_common::rviz_common
113117
)
114118

115-
116-
set(nav2_rviz_plugins_particle_cloud_display_headers_to_moc
117-
include/nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
118-
include/nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
119-
)
120-
121119
# Causes the visibility macros to use dllexport rather than dllimport,
122120
# which is appropriate when building the dll but not consuming it.
123121
# TODO: Make this specific to this project (not rviz default plugins)
124-
target_compile_definitions(nav2_rviz_plugins_goal PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
122+
target_compile_definitions(nav2_rviz_plugins PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
125123
# prevent pluginlib from using boost
126-
target_compile_definitions(nav2_rviz_plugins_goal PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
127-
128-
129-
add_library(nav2_rviz_plugins_particle_cloud_display SHARED
130-
src/particle_cloud_display/flat_weighted_arrows_array.cpp
131-
src/particle_cloud_display/particle_cloud_display.cpp
132-
${nav2_rviz_plugins_particle_cloud_display_headers_to_moc}
133-
)
134-
135-
ament_target_dependencies(nav2_rviz_plugins_particle_cloud_display
136-
${dependencies}
137-
)
138-
139-
target_include_directories(nav2_rviz_plugins_particle_cloud_display PUBLIC
140-
${Qt5Widgets_INCLUDE_DIRS}
141-
${OGRE_INCLUDE_DIRS}
142-
)
143-
144-
target_link_libraries(nav2_rviz_plugins_particle_cloud_display
145-
rviz_common::rviz_common
146-
)
147-
148-
target_compile_definitions(nav2_rviz_plugins_particle_cloud_display PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY")
149-
target_compile_definitions(nav2_rviz_plugins_particle_cloud_display PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
124+
target_compile_definitions(nav2_rviz_plugins PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
150125

151126
pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)
152127

153128
install(
154-
TARGETS nav2_rviz_plugins_goal
155-
EXPORT nav2_rviz_plugins_goal
156-
ARCHIVE DESTINATION lib
157-
LIBRARY DESTINATION lib
158-
RUNTIME DESTINATION bin
159-
INCLUDES DESTINATION include
160-
)
161-
162-
install(
163-
TARGETS nav2_rviz_plugins_particle_cloud_display
164-
EXPORT nav2_rviz_plugins_particle_cloud_display
129+
TARGETS nav2_rviz_plugins
130+
EXPORT nav2_rviz_plugins
165131
ARCHIVE DESTINATION lib
166132
LIBRARY DESTINATION lib
167133
RUNTIME DESTINATION bin
@@ -183,8 +149,20 @@ if(BUILD_TESTING)
183149
find_package(ament_cmake_gmock REQUIRED)
184150
find_package(ament_index_cpp REQUIRED)
185151
find_package(rviz_visual_testing_framework REQUIRED)
186-
find_package(rviz_common REQUIRED)
152+
find_package(geometry_msgs REQUIRED)
153+
find_package(nav2_util REQUIRED)
187154
find_package(nav2_msgs REQUIRED)
155+
find_package(nav_msgs REQUIRED)
156+
find_package(Qt5 REQUIRED COMPONENTS Core Gui Widgets Test Concurrent)
157+
find_package(rclcpp REQUIRED)
158+
find_package(rclcpp_lifecycle REQUIRED)
159+
find_package(rviz_common REQUIRED)
160+
find_package(rviz_default_plugins REQUIRED)
161+
find_package(rviz_ogre_vendor REQUIRED)
162+
find_package(rviz_rendering REQUIRED)
163+
find_package(std_msgs REQUIRED)
164+
find_package(tf2_geometry_msgs REQUIRED)
165+
find_package(visualization_msgs REQUIRED)
188166

189167
set(TEST_INCLUDE_DIRS
190168
${OGRE_INCLUDE_DIRS}
@@ -193,13 +171,26 @@ if(BUILD_TESTING)
193171
ament_include_directories_order(TEST_INCLUDE_DIRS ${TEST_INCLUDE_DIRS})
194172

195173
set(TEST_LINK_LIBRARIES
196-
nav2_rviz_plugins_particle_cloud_display
174+
rviz_common::rviz_common
175+
nav2_rviz_plugins
197176
)
198177

199178
set(TEST_TARGET_DEPENDENCIES
179+
geometry_msgs
180+
nav2_util
200181
nav2_msgs
201-
rviz_common
182+
nav_msgs
183+
Qt5
202184
rclcpp
185+
rviz_common
186+
rviz_default_plugins
187+
rviz_ogre_vendor
188+
rviz_rendering
189+
std_msgs
190+
tf2_geometry_msgs
191+
visualization_msgs
192+
pluginlib
193+
rclcpp_lifecycle
203194
)
204195

205196
ament_add_gmock(particle_cloud_display_test
@@ -232,17 +223,23 @@ if(BUILD_TESTING)
232223
endif()
233224

234225
ament_export_include_directories(include)
235-
ament_export_interfaces(nav2_rviz_plugins_goal HAS_LIBRARY_TARGET)
236-
ament_export_interfaces(nav2_rviz_plugins_particle_cloud_display HAS_LIBRARY_TARGET)
226+
ament_export_interfaces(nav2_rviz_plugins HAS_LIBRARY_TARGET)
237227
ament_export_dependencies(
238-
Qt5
239-
rviz_common
240228
geometry_msgs
241-
map_msgs
242-
nav_msgs
229+
nav2_util
243230
nav2_msgs
231+
nav_msgs
232+
Qt5
244233
rclcpp
234+
rviz_common
245235
rviz_default_plugins
236+
rviz_ogre_vendor
237+
rviz_rendering
238+
std_msgs
239+
tf2_geometry_msgs
240+
visualization_msgs
241+
pluginlib
242+
rclcpp_lifecycle
246243
)
247244

248245
ament_package()

0 commit comments

Comments
 (0)