@@ -63,29 +63,10 @@ find_package(std_msgs REQUIRED)
6363find_package (tf2_geometry_msgs REQUIRED)
6464find_package (visualization_msgs REQUIRED)
6565
66- set (nav2_rviz_plugins_headers_to_moc
67- include /nav2_rviz_plugins/goal_pose_updater
68- include /nav2_rviz_plugins/goal_common
69- include /nav2_rviz_plugins/goal_tool.hpp
70- include /nav2_rviz_plugins/nav2_panel.hpp
71- include /nav2_rviz_plugins/particle_cloud_display/flat_weighted_arrows_array.hpp
72- include /nav2_rviz_plugins/particle_cloud_display/particle_cloud_display.hpp
73- )
74-
7566include_directories (
7667 include
7768)
7869
79- set (library_name ${PROJECT_NAME} )
80-
81- add_library (${library_name} SHARED
82- src/goal_tool.cpp
83- src/nav2_panel.cpp
84- src/particle_cloud_display/flat_weighted_arrows_array.cpp
85- src/particle_cloud_display/particle_cloud_display.cpp
86- ${nav2_rviz_plugins_headers_to_moc}
87- )
88-
8970set (dependencies
9071 geometry_msgs
9172 nav2_util
@@ -104,32 +85,83 @@ set(dependencies
10485 tf2_geometry_msgs
10586)
10687
107- ament_target_dependencies(${library_name}
88+ set (nav2_rviz_plugins_goal_headers_to_moc
89+ include /nav2_rviz_plugins/ros_action_qevent.hpp
90+ include /nav2_rviz_plugins/goal_pose_updater
91+ include /nav2_rviz_plugins/goal_common
92+ include /nav2_rviz_plugins/goal_tool.hpp
93+ include /nav2_rviz_plugins/nav2_panel.hpp
94+ )
95+
96+ add_library (nav2_rviz_plugins_goal SHARED
97+ src/goal_tool.cpp
98+ src/nav2_panel.cpp
99+ ${nav2_rviz_plugins_goal_headers_to_moc}
100+ )
101+
102+ ament_target_dependencies(nav2_rviz_plugins_goal
108103 ${dependencies}
109104)
110105
111- target_include_directories (${library_name} PUBLIC
106+ target_include_directories (nav2_rviz_plugins_goal PUBLIC
112107 ${Qt5Widgets_INCLUDE_DIRS}
113108 ${OGRE_INCLUDE_DIRS}
114109)
115110
116- target_link_libraries (${library_name}
111+ target_link_libraries (nav2_rviz_plugins_goal
117112 rviz_common::rviz_common
118113)
119114
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+
120121# Causes the visibility macros to use dllexport rather than dllimport,
121122# which is appropriate when building the dll but not consuming it.
122123# TODO: Make this specific to this project (not rviz default plugins)
123- target_compile_definitions (${library_name} PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY" )
124-
124+ target_compile_definitions (nav2_rviz_plugins_goal PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY" )
125125# prevent pluginlib from using boost
126- target_compile_definitions (${library_name} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS" )
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" )
127150
128151pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)
129152
130153install (
131- TARGETS ${library_name}
132- EXPORT ${library_name}
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
133165 ARCHIVE DESTINATION lib
134166 LIBRARY DESTINATION lib
135167 RUNTIME DESTINATION bin
@@ -151,7 +183,8 @@ if(BUILD_TESTING)
151183 find_package (ament_cmake_gmock REQUIRED)
152184 find_package (ament_index_cpp REQUIRED)
153185 find_package (rviz_visual_testing_framework REQUIRED)
154- find_package (rviz_default_plugins REQUIRED)
186+ find_package (rviz_common REQUIRED)
187+ find_package (nav2_msgs REQUIRED)
155188
156189 set (TEST_INCLUDE_DIRS
157190 ${OGRE_INCLUDE_DIRS}
@@ -160,11 +193,12 @@ if(BUILD_TESTING)
160193 ament_include_directories_order(TEST_INCLUDE_DIRS ${TEST_INCLUDE_DIRS} )
161194
162195 set (TEST_LINK_LIBRARIES
163- ${library_name}
196+ nav2_rviz_plugins_particle_cloud_display
164197 )
165198
166199 set (TEST_TARGET_DEPENDENCIES
167200 nav2_msgs
201+ rviz_common
168202 rclcpp
169203 )
170204
@@ -198,7 +232,8 @@ if(BUILD_TESTING)
198232endif ()
199233
200234ament_export_include_directories(include )
201- ament_export_interfaces(${library_name} HAS_LIBRARY_TARGET)
235+ ament_export_interfaces(nav2_rviz_plugins_goal HAS_LIBRARY_TARGET)
236+ ament_export_interfaces(nav2_rviz_plugins_particle_cloud_display HAS_LIBRARY_TARGET)
202237ament_export_dependencies(
203238 Qt5
204239 rviz_common
0 commit comments