Skip to content

Commit

Permalink
Lint visualization (#1144)
Browse files Browse the repository at this point in the history
* Sort dependencies alphabetically
* Add missing dependencies
* Fix rostest deps
* Use CATKIN_GLOBAL_INCLUDE_DESTINATION
* Remove link_directories
  • Loading branch information
davetcoleman authored and rhaschke committed Oct 25, 2018
1 parent 6bcb710 commit 5007b5f
Show file tree
Hide file tree
Showing 7 changed files with 42 additions and 35 deletions.
32 changes: 18 additions & 14 deletions moveit_ros/visualization/CMakeLists.txt
Expand Up @@ -19,13 +19,19 @@ pkg_check_modules(OGRE OGRE)
link_directories( ${OGRE_LIBRARY_DIRS} )

find_package(catkin REQUIRED COMPONENTS
class_loader
eigen_conversions
geometric_shapes
interactive_markers
moveit_ros_perception
moveit_ros_planning_interface
moveit_ros_robot_interaction
moveit_ros_warehouse
moveit_ros_perception
geometric_shapes
interactive_markers
class_loader
object_recognition_msgs
pluginlib
rosconsole
roscpp
rospy
rviz
tf2_eigen
roscpp
Expand Down Expand Up @@ -62,20 +68,21 @@ add_definitions(-DQT_NO_KEYWORDS)

catkin_package(
LIBRARIES
moveit_rviz_plugin_render_tools
moveit_robot_state_rviz_plugin_core
moveit_motion_planning_rviz_plugin_core
moveit_trajectory_rviz_plugin_core
moveit_planning_scene_rviz_plugin_core
moveit_robot_state_rviz_plugin_core
moveit_rviz_plugin_render_tools
moveit_trajectory_rviz_plugin_core
INCLUDE_DIRS
rviz_plugin_render_tools/include
robot_state_rviz_plugin/include
planning_scene_rviz_plugin/include
motion_planning_rviz_plugin/include
planning_scene_rviz_plugin/include
robot_state_rviz_plugin/include
rviz_plugin_render_tools/include
trajectory_rviz_plugin/include
CATKIN_DEPENDS
moveit_ros_planning_interface
moveit_ros_robot_interaction
object_recognition_msgs
DEPENDS
EIGEN3
)
Expand All @@ -96,9 +103,6 @@ include_directories(SYSTEM
${QT_INCLUDE_DIR}
${OGRE_INCLUDE_DIRS})

link_directories(${Boost_LIBRARY_DIRS})
link_directories(${catkin_LIBRARY_DIRS})

add_subdirectory(rviz_plugin_render_tools)
add_subdirectory(robot_state_rviz_plugin)
add_subdirectory(planning_scene_rviz_plugin)
Expand All @@ -115,6 +119,6 @@ install(FILES
install(DIRECTORY icons DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

if (CATKIN_ENABLE_TESTING)
find_package(rostest)
find_package(rostest REQUIRED)
add_rostest(test/moveit_joy.test)
endif()
Expand Up @@ -36,7 +36,7 @@ add_library(${MOVEIT_LIB_NAME} src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(DIRECTORY include/ DESTINATION include)
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
35 changes: 19 additions & 16 deletions moveit_ros/visualization/package.xml
Expand Up @@ -20,35 +20,38 @@
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>pkg-config</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rviz</build_depend>
<build_depend>class_loader</build_depend>
<build_depend>eigen</build_depend>
<build_depend>eigen_conversions</build_depend>
<build_depend>geometric_shapes</build_depend>
<build_depend>interactive_markers</build_depend>
<build_depend>libogre-dev</build_depend>
<build_depend>qtbase5-dev</build_depend>
<build_depend>libqt5-opengl-dev</build_depend>
<build_depend>moveit_ros_robot_interaction</build_depend>
<build_depend>moveit_ros_perception</build_depend>
<build_depend>moveit_ros_planning_interface</build_depend>
<build_depend>moveit_ros_warehouse</build_depend>
<build_depend>moveit_ros_robot_interaction</build_depend>
<build_depend version_gte="1.11.2">pluginlib</build_depend>
<build_depend>interactive_markers</build_depend>
<build_depend>geometric_shapes</build_depend>
<build_depend>object_recognition_msgs</build_depend>
<build_depend>moveit_ros_perception</build_depend>
<build_depend>eigen</build_depend>
<build_depend version_gte="1.11.2">pluginlib</build_depend>
<build_depend>qtbase5-dev</build_depend>
<build_depend>rosconsole</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>rviz</build_depend>
<build_depend>tf2_eigen</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>rviz</run_depend>
<run_depend>geometric_shapes</run_depend>
<run_depend>interactive_markers</run_depend>
<run_depend>moveit_ros_robot_interaction</run_depend>
<run_depend>moveit_ros_perception</run_depend>
<run_depend>moveit_ros_planning_interface</run_depend>
<run_depend>moveit_ros_warehouse</run_depend>
<run_depend>moveit_ros_robot_interaction</run_depend>
<run_depend version_gte="1.11.2">pluginlib</run_depend>
<run_depend>interactive_markers</run_depend>
<run_depend>geometric_shapes</run_depend>
<run_depend>object_recognition_msgs</run_depend>
<run_depend>moveit_ros_perception</run_depend>
<run_depend version_gte="1.11.2">pluginlib</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>tf2_eigen</run_depend>
<run_depend>rviz</run_depend>

<test_depend>rostest</test_depend>

Expand Down
Expand Up @@ -15,7 +15,7 @@ add_library(${MOVEIT_LIB_NAME} src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(DIRECTORY include/ DESTINATION include)
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
Expand Up @@ -11,7 +11,7 @@ add_library(${MOVEIT_LIB_NAME} src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(DIRECTORY include/ DESTINATION include)
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
Expand Up @@ -31,7 +31,7 @@ target_link_libraries(${MOVEIT_LIB_NAME}
${Boost_LIBRARIES}
)

install(DIRECTORY include/ DESTINATION include)
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(TARGETS ${MOVEIT_LIB_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
Expand Up @@ -24,7 +24,7 @@ add_library(${MOVEIT_LIB_NAME} src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(DIRECTORY include/ DESTINATION include)
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down

0 comments on commit 5007b5f

Please sign in to comment.