Skip to content

Commit

Permalink
Fix sub-components
Browse files Browse the repository at this point in the history
  • Loading branch information
kazuki0824 committed Jul 5, 2019
1 parent 5148686 commit 3c709af
Show file tree
Hide file tree
Showing 8 changed files with 27 additions and 8 deletions.
4 changes: 4 additions & 0 deletions moveit_kinematics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,11 @@ find_package(ament_cmake REQUIRED)
find_package(Boost REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(orocos_kdl REQUIRED)
find_package(tf2_kdl REQUIRED)
find_package(kdl_parser REQUIRED)
find_package(rclcpp REQUIRED)
find_package(random_numbers REQUIRED)
find_package(class_loader REQUIRED)
find_package(pluginlib REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_ros_planning REQUIRED)
Expand All @@ -28,6 +30,8 @@ ament_export_libraries(${PROJECT_NAME} kdl_kinematics_plugin)

include_directories(${THIS_PACKAGE_INCLUDE_DIRS}
${rclcpp_INCLUDE_DIRS}
${tf2_kdl_INCLUDE_DIRS}
${class_loader_INCLUDE_DIRS}
${random_numbers_INCLUDE_DIRS}
${moveit_msgs_INCLUDE_DIRS}
${moveit_core_INCLUDE_DIRS}
Expand Down
4 changes: 3 additions & 1 deletion moveit_kinematics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,10 @@
<url type="repository">https://github.com/ros-planning/moveit</url>
<url type="bugtracker">https://github.com/ros-planning/moveit/issues</url>

<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>moveit_core</depend>
<depend>class_loader</depend>
<depend>pluginlib</depend>
<depend>eigen</depend>
<depend>moveit_ros_planning</depend>
Expand All @@ -32,6 +33,7 @@

<exec_depend>python-lxml</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>moveit_resources</test_depend>

<export>
Expand Down
7 changes: 6 additions & 1 deletion moveit_ros/manipulation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(moveit_ros_planning REQUIRED)
find_package(moveit_ros_move_group REQUIRED)
find_package(message_filters REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(pluginlib REQUIRED)
Expand All @@ -26,8 +27,12 @@ include_directories(pick_place/include)
include_directories(move_group_pick_place_capability/include)

include_directories(${rclcpp_INCLUDE_DIRS}
${rclcpp_action_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${moveit_core_INCLUDE_DIRS})
${message_filters_INCLUDE_DIRS}
${moveit_core_INCLUDE_DIRS}
${moveit_ros_planning_INCLUDE_DIRS}
${moveit_ros_move_group_INCLUDE_DIRS})
include_directories(SYSTEM
${EIGEN3_INCLUDE_DIRS})

Expand Down
3 changes: 2 additions & 1 deletion moveit_ros/move_group/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ find_package(std_srvs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(message_filters REQUIRED)

include_directories(include)
include_directories(include ${message_filters_INCLUDE_DIRS})

add_library(moveit_move_group_capabilities_base SHARED
src/move_group_context.cpp
Expand Down
2 changes: 2 additions & 0 deletions moveit_ros/planning/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
include_directories(${THIS_PACKAGE_INCLUDE_DIRS}
${rclcpp_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${pluginlib_INCLUDE_DIRS}
${srdfdom_INCLUDE_DIRS}
${moveit_core_INCLUDE_DIRS}
)
include_directories(SYSTEM
Expand Down
3 changes: 2 additions & 1 deletion moveit_ros/planning/planning_scene_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
set(MOVEIT_LIB_NAME moveit_planning_scene_monitor)

include_directories(${moveit_ros_perception_INCLUDE_DIRS})
add_library(${MOVEIT_LIB_NAME} SHARED
src/planning_scene_monitor.cpp
src/current_state_monitor.cpp
Expand All @@ -8,7 +9,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
ament_target_dependencies(${MOVEIT_LIB_NAME}
moveit_collision_plugin_loader
# moveit_occupancy_map_monitor
moveit_occupancy_map_monitor
moveit_ros_perception
message_filters
urdf
Expand Down
10 changes: 7 additions & 3 deletions moveit_ros/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ find_package(moveit_msgs REQUIRED)
# TODO: uncomment this as submodules become available
find_package(moveit_ros_planning REQUIRED)
# find_package(moveit_ros_warehouse REQUIRED)
# find_package(moveit_ros_manipulation REQUIRED)
find_package(moveit_ros_manipulation REQUIRED)
find_package(message_filters REQUIRED)
find_package(moveit_ros_move_group REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2 REQUIRED)
Expand Down Expand Up @@ -63,7 +64,7 @@ set(THIS_PACKAGE_INCLUDE_LIBRARIES
set(THIS_PACKAGE_INCLUDE_DEPENDENCIES
moveit_ros_planning
# moveit_ros_warehouse
# moveit_ros_manipulation
moveit_ros_manipulation
moveit_ros_move_group
geometry_msgs
moveit_msgs
Expand All @@ -73,7 +74,10 @@ set(THIS_PACKAGE_INCLUDE_DEPENDENCIES

include_directories(${THIS_PACKAGE_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS})
${message_filters_INCLUDE_DIRS}
${moveit_ros_planning_INCLUDE_DIRS}
${moveit_ros_move_group_INCLUDE_DIRS}
${moveit_ros_manipulation_INCLUDE_DIRS})

include_directories(SYSTEM
${EIGEN3_INCLUDE_DIRS}
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/planning_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<depend>moveit_ros_planning</depend>
<!-- <depend>moveit_ros_warehouse</depend> TODO: uncomment when ported-->
<depend>moveit_ros_move_group</depend>
<!-- <depend>moveit_ros_manipulation</depend> TODO: uncomment when ported -->
<depend>moveit_ros_manipulation</depend>
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>geometry_msgs</depend>
Expand Down

0 comments on commit 3c709af

Please sign in to comment.