diff --git a/costmap_2d/CMakeLists.txt b/costmap_2d/CMakeLists.txt index 2a5b903428..00365b834d 100644 --- a/costmap_2d/CMakeLists.txt +++ b/costmap_2d/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(catkin REQUIRED sensor_msgs std_msgs tf + visualization_msgs voxel_grid ) @@ -60,8 +61,6 @@ generate_dynamic_reconfigure_options( catkin_package( INCLUDE_DIRS include - ${EIGEN_INCLUDE_DIRS} - ${PCL_INCLUDE_DIRS} LIBRARIES costmap_2d layers CATKIN_DEPENDS dynamic_reconfigure @@ -77,6 +76,7 @@ catkin_package( sensor_msgs std_msgs tf + visualization_msgs voxel_grid DEPENDS PCL @@ -96,7 +96,7 @@ add_library(costmap_2d src/footprint.cpp src/costmap_layer.cpp ) -add_dependencies(costmap_2d geometry_msgs_gencpp) +add_dependencies(costmap_2d ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(costmap_2d ${PCL_LIBRARIES} ${Boost_LIBRARIES} @@ -114,18 +114,17 @@ target_link_libraries(layers costmap_2d ) -add_dependencies(costmap_2d costmap_2d_gencfg) -add_dependencies(layers costmap_2d_gencfg) -add_dependencies(costmap_2d costmap_2d_gencpp) +add_dependencies(costmap_2d costmap_2d_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +add_dependencies(layers costmap_2d_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) add_executable(costmap_2d_markers src/costmap_2d_markers.cpp) -add_dependencies(costmap_2d_markers visualization_msgs_gencpp) +add_dependencies(costmap_2d_markers ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(costmap_2d_markers costmap_2d ) add_executable(costmap_2d_cloud src/costmap_2d_cloud.cpp) -add_dependencies(costmap_2d_cloud sensor_msgs_gencpp) +add_dependencies(costmap_2d_cloud ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(costmap_2d_cloud costmap_2d ) diff --git a/navfn/CMakeLists.txt b/navfn/CMakeLists.txt index ad01c3a487..0a31d9ba74 100644 --- a/navfn/CMakeLists.txt +++ b/navfn/CMakeLists.txt @@ -6,11 +6,13 @@ find_package(catkin REQUIRED cmake_modules costmap_2d geometry_msgs + message_generation nav_core nav_msgs pcl_conversions pcl_ros pluginlib + rosconsole roscpp tf visualization_msgs @@ -38,9 +40,7 @@ add_service_files( generate_messages( DEPENDENCIES - std_msgs geometry_msgs - nav_msgs ) catkin_package( @@ -49,9 +49,13 @@ catkin_package( LIBRARIES navfn CATKIN_DEPENDS + geometry_msgs + message_runtime nav_core - roscpp + nav_msgs pluginlib + roscpp + visualization_msgs ) add_library (navfn src/navfn.cpp src/navfn_ros.cpp) diff --git a/navfn/package.xml b/navfn/package.xml index f1b8f00537..691eab2577 100644 --- a/navfn/package.xml +++ b/navfn/package.xml @@ -24,6 +24,7 @@ cmake_modules costmap_2d geometry_msgs + message_generation nav_core nav_msgs netpbm @@ -37,6 +38,7 @@ costmap_2d geometry_msgs + message_runtime nav_core nav_msgs pcl_conversions @@ -47,6 +49,8 @@ tf visualization_msgs + rosunit + diff --git a/robot_pose_ekf/CMakeLists.txt b/robot_pose_ekf/CMakeLists.txt index 0b26f99208..8c623d4777 100644 --- a/robot_pose_ekf/CMakeLists.txt +++ b/robot_pose_ekf/CMakeLists.txt @@ -35,7 +35,12 @@ generate_messages( catkin_package( CATKIN_DEPENDS + geometry_msgs + message_runtime + nav_msgs roscpp + sensor_msgs + std_msgs ) include_directories( @@ -53,7 +58,7 @@ target_link_libraries(robot_pose_ekf ${Boost_LIBRARIES} ${BFL_LIBRARIES} ) -add_dependencies(robot_pose_ekf robot_pose_ekf_gencpp) +add_dependencies(robot_pose_ekf ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) install( TARGETS @@ -84,6 +89,7 @@ target_link_libraries(test_robot_pose_ekf ${BFL_LIBRARIES} gtest ) +add_dependencies(test_robot_pose_ekf ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) catkin_download_test_data( download_data_zero_covariance.bag @@ -98,6 +104,7 @@ target_link_libraries(test_robot_pose_ekf_zero_covariance ${BFL_LIBRARIES} gtest ) +add_dependencies(test_robot_pose_ekf_zero_covariance ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) # This has to be done after we've already built targets, or catkin variables get borked find_package(rostest) diff --git a/robot_pose_ekf/package.xml b/robot_pose_ekf/package.xml index 8d8e14e23e..688b780a07 100644 --- a/robot_pose_ekf/package.xml +++ b/robot_pose_ekf/package.xml @@ -15,6 +15,7 @@ catkin + message_generation roscpp rostest bfl @@ -24,6 +25,7 @@ nav_msgs tf + message_runtime roscpp rostest bfl