Skip to content

Commit

Permalink
Fix errors: catkin_lint 1.6.7 (moveit#1987)
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser authored and rhaschke committed Mar 28, 2020
1 parent ef94c36 commit 7d0cc82
Show file tree
Hide file tree
Showing 15 changed files with 38 additions and 10 deletions.
3 changes: 2 additions & 1 deletion moveit_kinematics/CMakeLists.txt
Expand Up @@ -32,8 +32,9 @@ catkin_package(
INCLUDE_DIRS
${THIS_PACKAGE_INCLUDE_DIRS}
CATKIN_DEPENDS
pluginlib
moveit_core
pluginlib
roscpp
DEPENDS
EIGEN3
)
Expand Down
2 changes: 2 additions & 0 deletions moveit_planners/ompl/CMakeLists.txt
Expand Up @@ -31,7 +31,9 @@ catkin_package(
INCLUDE_DIRS
ompl_interface/include
CATKIN_DEPENDS
dynamic_reconfigure
moveit_core
roscpp
DEPENDS
OMPL
)
Expand Down
Expand Up @@ -21,6 +21,7 @@ catkin_package(
INCLUDE_DIRS
CATKIN_DEPENDS
moveit_core
roscpp
)

include_directories(${Boost_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})
Expand Down
Expand Up @@ -25,6 +25,7 @@ catkin_package(
CATKIN_DEPENDS
moveit_core
moveit_ros_planning
roscpp
)

add_library(${PROJECT_NAME}
Expand Down
3 changes: 2 additions & 1 deletion moveit_plugins/moveit_ros_control_interface/CMakeLists.txt
Expand Up @@ -22,8 +22,9 @@ catkin_package(
${PROJECT_NAME}_plugin
${PROJECT_NAME}_trajectory_plugin
CATKIN_DEPENDS
moveit_core
actionlib
controller_manager_msgs
moveit_core
trajectory_msgs
DEPENDS Boost
)
Expand Down
12 changes: 9 additions & 3 deletions moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt
Expand Up @@ -22,9 +22,15 @@ find_package(catkin COMPONENTS
include_directories(include ${Boost_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})

catkin_package(
LIBRARIES ${PROJECT_NAME}
INCLUDE_DIRS include
CATKIN_DEPENDS moveit_core actionlib control_msgs
LIBRARIES
${PROJECT_NAME}
INCLUDE_DIRS
include
CATKIN_DEPENDS
actionlib
control_msgs
moveit_core
roscpp
)

add_library(${PROJECT_NAME}
Expand Down
3 changes: 3 additions & 0 deletions moveit_ros/manipulation/CMakeLists.txt
Expand Up @@ -33,9 +33,12 @@ catkin_package(
LIBRARIES
moveit_pick_place_planner
CATKIN_DEPENDS
actionlib
dynamic_reconfigure
moveit_core
moveit_msgs
moveit_ros_planning
roscpp
DEPENDS
EIGEN3
)
Expand Down
3 changes: 3 additions & 0 deletions moveit_ros/move_group/CMakeLists.txt
Expand Up @@ -28,8 +28,11 @@ catkin_package(
INCLUDE_DIRS
include
CATKIN_DEPENDS
actionlib
moveit_core
moveit_ros_planning
roscpp
std_srvs
tf2_geometry_msgs
)

Expand Down
1 change: 1 addition & 0 deletions moveit_ros/perception/CMakeLists.txt
Expand Up @@ -67,6 +67,7 @@ catkin_package(
moveit_msgs
moveit_ros_occupancy_map_monitor
object_recognition_msgs
roscpp
sensor_msgs
tf2_geometry_msgs
DEPENDS
Expand Down
5 changes: 4 additions & 1 deletion moveit_ros/planning/CMakeLists.txt
Expand Up @@ -63,10 +63,13 @@ catkin_package(
INCLUDE_DIRS
${THIS_PACKAGE_INCLUDE_DIRS}
CATKIN_DEPENDS
pluginlib
actionlib
dynamic_reconfigure
moveit_core
moveit_ros_occupancy_map_monitor
moveit_msgs
pluginlib
roscpp
tf2_msgs
tf2_geometry_msgs
DEPENDS
Expand Down
5 changes: 3 additions & 2 deletions moveit_ros/planning_interface/CMakeLists.txt
Expand Up @@ -66,12 +66,13 @@ catkin_package(
${THIS_PACKAGE_INCLUDE_DIRS}
CATKIN_DEPENDS
actionlib
geometry_msgs
moveit_msgs
moveit_ros_planning
moveit_ros_warehouse
moveit_ros_manipulation
moveit_ros_move_group
geometry_msgs
moveit_msgs
roscpp
tf2_geometry_msgs
DEPENDS
EIGEN3
Expand Down
3 changes: 2 additions & 1 deletion moveit_ros/robot_interaction/CMakeLists.txt
Expand Up @@ -28,8 +28,9 @@ catkin_package(
INCLUDE_DIRS
include
CATKIN_DEPENDS
moveit_ros_planning
interactive_markers
moveit_ros_planning
roscpp
tf2_geometry_msgs
)

Expand Down
1 change: 1 addition & 0 deletions moveit_ros/visualization/CMakeLists.txt
Expand Up @@ -80,6 +80,7 @@ catkin_package(
moveit_ros_planning_interface
moveit_ros_robot_interaction
object_recognition_msgs
roscpp
DEPENDS
EIGEN3
)
Expand Down
4 changes: 3 additions & 1 deletion moveit_ros/warehouse/CMakeLists.txt
Expand Up @@ -27,7 +27,9 @@ catkin_package(
warehouse/include
CATKIN_DEPENDS
moveit_ros_planning
warehouse_ros)
warehouse_ros
roscpp
)

include_directories(warehouse/include)
include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
Expand Down
1 change: 1 addition & 0 deletions moveit_setup_assistant/CMakeLists.txt
Expand Up @@ -55,6 +55,7 @@ catkin_package(
CATKIN_DEPENDS
moveit_ros_planning
moveit_ros_visualization
roscpp
)

# Header files that need Qt Moc pre-processing for use with Qt signals, etc:
Expand Down

0 comments on commit 7d0cc82

Please sign in to comment.