Skip to content

Commit

Permalink
Fix CMakeLists + package.xmls
Browse files Browse the repository at this point in the history
This fixes compilation errors when rosjava is installed on the system.
It also removes a lot of errors reported by catkin_lint.

Fixes #537 .
  • Loading branch information
mintar committed Dec 1, 2016
1 parent b4e1341 commit 35fb9de
Show file tree
Hide file tree
Showing 5 changed files with 28 additions and 12 deletions.
15 changes: 7 additions & 8 deletions costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ find_package(catkin REQUIRED
sensor_msgs
std_msgs
tf
visualization_msgs
voxel_grid
)

Expand Down Expand Up @@ -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
Expand All @@ -77,6 +76,7 @@ catkin_package(
sensor_msgs
std_msgs
tf
visualization_msgs
voxel_grid
DEPENDS
PCL
Expand All @@ -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}
Expand All @@ -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
)
Expand Down
10 changes: 7 additions & 3 deletions navfn/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -38,9 +40,7 @@ add_service_files(

generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
nav_msgs
)

catkin_package(
Expand All @@ -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)
Expand Down
4 changes: 4 additions & 0 deletions navfn/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<build_depend>cmake_modules</build_depend>
<build_depend>costmap_2d</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>nav_core</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>netpbm</build_depend> <!-- This is a test dependency -->
Expand All @@ -37,6 +38,7 @@

<run_depend>costmap_2d</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>nav_core</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>pcl_conversions</run_depend>
Expand All @@ -47,6 +49,8 @@
<run_depend>tf</run_depend>
<run_depend>visualization_msgs</run_depend>

<test_depend>rosunit</test_depend>

<export>
<nav_core plugin="${prefix}/bgp_plugin.xml" />
</export>
Expand Down
9 changes: 8 additions & 1 deletion robot_pose_ekf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,12 @@ generate_messages(

catkin_package(
CATKIN_DEPENDS
geometry_msgs
message_runtime
nav_msgs
roscpp
sensor_msgs
std_msgs
)

include_directories(
Expand All @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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)
Expand Down
2 changes: 2 additions & 0 deletions robot_pose_ekf/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>message_generation</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
<build_depend>bfl</build_depend>
Expand All @@ -24,6 +25,7 @@
<build_depend>nav_msgs</build_depend>
<build_depend>tf</build_depend>

<run_depend>message_runtime</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rostest</run_depend>
<run_depend>bfl</run_depend>
Expand Down

0 comments on commit 35fb9de

Please sign in to comment.