Skip to content

Commit

Permalink
Merge pull request #529 from vrabaud/kinetic_cmake_fix
Browse files Browse the repository at this point in the history
make all tests green
  • Loading branch information
mikeferguson authored Oct 24, 2016
2 parents ef605fd + 7865509 commit 76712c9
Show file tree
Hide file tree
Showing 12 changed files with 44 additions and 38 deletions.
13 changes: 7 additions & 6 deletions base_local_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,16 @@ find_package(Boost REQUIRED
thread
)

find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

catkin_python_setup()

Expand Down Expand Up @@ -92,8 +93,8 @@ add_library(base_local_planner
src/trajectory.cpp
src/voxel_grid_model.cpp)
add_dependencies(base_local_planner base_local_planner_gencfg)
add_dependencies(base_local_planner base_local_planner_gencpp)
add_dependencies(base_local_planner nav_msgs_gencpp)
add_dependencies(base_local_planner base_local_planner_generate_messages_cpp)
add_dependencies(base_local_planner nav_msgs_generate_messages_cpp)
target_link_libraries(base_local_planner
${catkin_LIBRARIES}
${PCL_LIBRARIES}
Expand All @@ -104,7 +105,7 @@ target_link_libraries(base_local_planner
add_library(trajectory_planner_ros
src/trajectory_planner.cpp
src/trajectory_planner_ros.cpp)
add_dependencies(trajectory_planner_ros nav_msgs_gencpp)
add_dependencies(trajectory_planner_ros nav_msgs_generate_messages_cpp)
target_link_libraries(trajectory_planner_ros
base_local_planner)

Expand Down
2 changes: 1 addition & 1 deletion carrot_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ include_directories(
include
${catkin_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

catkin_package(
INCLUDE_DIRS include
Expand Down
8 changes: 4 additions & 4 deletions clear_costmap_recovery/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,16 @@ find_package(catkin REQUIRED
tf
)

find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

catkin_package(
INCLUDE_DIRS include
Expand Down Expand Up @@ -49,7 +50,6 @@ if(CATKIN_ENABLE_TESTING)

# Create targets for test executables
add_rostest_gtest(clear_tester test/clear_tests.launch test/clear_tester.cpp)
add_dependencies(tests clear_tester ${catkin_LIBRARIES})
target_link_libraries(clear_tester clear_costmap_recovery ${GTEST_LIBRARIES})
endif()

Expand Down
12 changes: 7 additions & 5 deletions costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,23 @@ find_package(catkin REQUIRED
sensor_msgs
std_msgs
tf
visualization_msgs
voxel_grid
)

find_package(PCL REQUIRED)
find_package(Eigen REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
find_package(Eigen3 REQUIRED)
find_package(Boost REQUIRED COMPONENTS system thread)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)

add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

# messages
add_message_files(
Expand Down Expand Up @@ -60,7 +62,7 @@ generate_dynamic_reconfigure_options(
catkin_package(
INCLUDE_DIRS
include
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
LIBRARIES costmap_2d layers
CATKIN_DEPENDS
Expand All @@ -80,7 +82,7 @@ catkin_package(
voxel_grid
DEPENDS
PCL
Eigen
EIGEN3
Boost
)

Expand Down
9 changes: 5 additions & 4 deletions dwa_local_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,16 @@ find_package(catkin REQUIRED
tf
)

find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

link_directories(${catkin_LIBRARY_DIRS})

Expand All @@ -44,7 +45,7 @@ catkin_package(
add_library(dwa_local_planner src/dwa_planner.cpp src/dwa_planner_ros.cpp)
target_link_libraries(dwa_local_planner ${catkin_LIBRARIES})
add_dependencies(dwa_local_planner dwa_local_planner_gencfg)
add_dependencies(dwa_local_planner nav_msgs_gencpp)
add_dependencies(dwa_local_planner nav_msgs_generate_messages_cpp)

install(TARGETS dwa_local_planner
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
4 changes: 2 additions & 2 deletions fake_localization/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ target_link_libraries(fake_localization
${Boost_LIBRARIES}
)

add_dependencies(fake_localization nav_msgs_gencpp)
add_dependencies(fake_localization geometry_msgs_gencpp)
add_dependencies(fake_localization nav_msgs_generate_messages_cpp)
add_dependencies(fake_localization geometry_msgs_generate_messages_cpp)

install(
PROGRAMS
Expand Down
2 changes: 1 addition & 1 deletion map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ if(CATKIN_ENABLE_TESTING)
gtest
${catkin_LIBRARIES}
)
add_dependencies(rtest nav_msgs_gencpp)
add_dependencies(rtest nav_msgs_generate_messages_cpp)

# This has to be done after we've already built targets, or catkin variables get borked
find_package(rostest)
Expand Down
8 changes: 4 additions & 4 deletions move_base/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@ find_package(catkin REQUIRED
nav_core
tf
)
find_package(Eigen REQUIRED)
add_definitions(${EIGEN_DEFINITIONS})
find_package(Eigen3 REQUIRED)
add_definitions(${EIGEN3_DEFINITIONS})

# dynamic reconfigure
generate_dynamic_reconfigure_options(
Expand All @@ -30,7 +30,7 @@ catkin_package(
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
)

# move_base
Expand All @@ -42,7 +42,7 @@ target_link_libraries(move_base
${catkin_LIBRARIES}
)
add_dependencies(move_base move_base_gencfg)
add_dependencies(move_base geometry_msgs_gencpp)
add_dependencies(move_base geometry_msgs_generate_messages_cpp)

add_executable(move_base_node
src/move_base_node.cpp
Expand Down
9 changes: 5 additions & 4 deletions move_slow_and_clear/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,18 @@ find_package(catkin REQUIRED
)


find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
find_package(Boost REQUIRED COMPONENTS thread)
include_directories(
include
${catkin_INCLUDE_DIRS}
SYSTEM
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

catkin_package(
INCLUDE_DIRS include
Expand All @@ -35,7 +36,7 @@ catkin_package(
)

add_library(${PROJECT_NAME} src/move_slow_and_clear.cpp)
add_dependencies(${PROJECT_NAME} geometry_msgs_gencpp)
add_dependencies(${PROJECT_NAME} geometry_msgs_generate_messages_cpp)
target_link_libraries(${PROJECT_NAME}
${Boost_LIBRARIES}
${catkin_LIBRARIES}
Expand Down
7 changes: 4 additions & 3 deletions navfn/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,17 @@ find_package(catkin REQUIRED
visualization_msgs
)

find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
remove_definitions(-DDISABLE_LIBUSB-1.0)
include_directories(
include
${catkin_INCLUDE_DIRS}
SYSTEM
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})


# services
Expand Down
2 changes: 1 addition & 1 deletion robot_pose_ekf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,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 robot_pose_ekf_generate_messages_cpp)

install(
TARGETS
Expand Down
6 changes: 3 additions & 3 deletions rotate_recovery/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@ find_package(catkin REQUIRED
base_local_planner
)

find_package(Eigen REQUIRED)
find_package(Eigen3 REQUIRED)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
)
add_definitions(${EIGEN_DEFINITIONS})
add_definitions(${EIGEN3_DEFINITIONS})

catkin_package(
INCLUDE_DIRS include
Expand Down

0 comments on commit 76712c9

Please sign in to comment.