@@ -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
151126pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)
152127
153128install (
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,10 @@ 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)
187152 find_package (nav2_msgs REQUIRED)
153+ find_package (rclcpp REQUIRED)
154+ find_package (rviz_common REQUIRED)
155+ find_package (rviz_default_plugins REQUIRED)
188156
189157 set (TEST_INCLUDE_DIRS
190158 ${OGRE_INCLUDE_DIRS}
@@ -193,13 +161,14 @@ if(BUILD_TESTING)
193161 ament_include_directories_order(TEST_INCLUDE_DIRS ${TEST_INCLUDE_DIRS} )
194162
195163 set (TEST_LINK_LIBRARIES
196- nav2_rviz_plugins_particle_cloud_display
164+ nav2_rviz_plugins
197165 )
198166
199167 set (TEST_TARGET_DEPENDENCIES
200168 nav2_msgs
201- rviz_common
202169 rclcpp
170+ rviz_common
171+ rviz_default_plugins
203172 )
204173
205174 ament_add_gmock(particle_cloud_display_test
@@ -232,17 +201,23 @@ if(BUILD_TESTING)
232201endif ()
233202
234203ament_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)
204+ ament_export_interfaces(nav2_rviz_plugins HAS_LIBRARY_TARGET)
237205ament_export_dependencies(
238- Qt5
239- rviz_common
240206 geometry_msgs
241- map_msgs
242- nav_msgs
207+ nav2_util
243208 nav2_msgs
209+ nav_msgs
210+ Qt5
244211 rclcpp
212+ rviz_common
245213 rviz_default_plugins
214+ rviz_ogre_vendor
215+ rviz_rendering
216+ std_msgs
217+ tf2_geometry_msgs
218+ visualization_msgs
219+ pluginlib
220+ rclcpp_lifecycle
246221)
247222
248223ament_package()
0 commit comments