Skip to content

Commit

Permalink
Fix CMakeLists + package.xmls (#548)
Browse files Browse the repository at this point in the history
* Fix CMakeLists + package.xmls

This fixes compilation errors when rosjava is installed on the system.
It also removes a lot of errors reported by catkin_lint.

Fixes #537 .

* Fix more CMakeLists.txt + package.xmls

* amcl: disambiguate include path

This fixes the following catkin_lint warning:

    amcl: warning: include paths 'include/amcl/map' and 'include' are ambiguous
         * You have used two include paths where one is a parent of the
         * other. Thus the same headers can be included with two different
         * include paths which may confuse users. It is recommended that
         * you keep your include paths consistent.
  • Loading branch information
mintar authored and mikeferguson committed Jul 31, 2017
1 parent 3eddfc6 commit a013a01
Show file tree
Hide file tree
Showing 37 changed files with 138 additions and 111 deletions.
7 changes: 5 additions & 2 deletions amcl/CMakeLists.txt
Expand Up @@ -3,8 +3,10 @@ project(amcl)

find_package(catkin REQUIRED
COMPONENTS
message_filters
rosbag
roscpp
std_srvs
tf
dynamic_reconfigure
nav_msgs
Expand All @@ -24,11 +26,12 @@ catkin_package(
roscpp
dynamic_reconfigure
tf
CATKIN_DEPENDS nav_msgs std_srvs
INCLUDE_DIRS include
LIBRARIES amcl_sensors amcl_map amcl_pf
)

include_directories(include/amcl include/amcl/map include/amcl/sensors include/amcl/pf)
include_directories(include)
include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

add_library(amcl_pf
Expand All @@ -55,7 +58,7 @@ target_link_libraries(amcl_sensors amcl_map amcl_pf)

add_executable(amcl
src/amcl_node.cpp)
add_dependencies(amcl amcl_gencfg)
add_dependencies(amcl ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

target_link_libraries(amcl
amcl_sensors amcl_map amcl_pf
Expand Down
3 changes: 2 additions & 1 deletion amcl/package.xml
Expand Up @@ -27,7 +27,6 @@
<build_depend>message_filters</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>tf</build_depend>

Expand All @@ -36,6 +35,8 @@
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>tf</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>std_srvs</run_depend>

<test_depend>rostest</test_depend>
<test_depend>map_server</test_depend>
</package>
2 changes: 1 addition & 1 deletion amcl/src/amcl/map/map.c
Expand Up @@ -31,7 +31,7 @@
#include <string.h>
#include <stdio.h>

#include "map.h"
#include "amcl/map/map.h"


// Create a new map
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/map/map_cspace.cpp
Expand Up @@ -23,7 +23,7 @@
#include <math.h>
#include <stdlib.h>
#include <string.h>
#include "map.h"
#include "amcl/map/map.h"

class CellData
{
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/map/map_draw.c
Expand Up @@ -33,7 +33,7 @@
#include <string.h>

#include <rtk.h>
#include "map.h"
#include "amcl/map/map.h"


////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/map/map_range.c
Expand Up @@ -30,7 +30,7 @@
#include <string.h>
#include <stdlib.h>

#include "map.h"
#include "amcl/map/map.h"

// Extract a single range reading from the map. Unknown cells and/or
// out-of-bound cells are treated as occupied, which makes it easy to
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/map/map_store.c
Expand Up @@ -31,7 +31,7 @@
#include <stdlib.h>
#include <string.h>

#include "map.h"
#include "amcl/map/map.h"


////////////////////////////////////////////////////////////////////////////
Expand Down
6 changes: 3 additions & 3 deletions amcl/src/amcl/pf/pf.c
Expand Up @@ -30,9 +30,9 @@
#include <stdlib.h>
#include <time.h>

#include "pf.h"
#include "pf_pdf.h"
#include "pf_kdtree.h"
#include "amcl/pf/pf.h"
#include "amcl/pf/pf_pdf.h"
#include "amcl/pf/pf_kdtree.h"


// Compute the required number of samples, given that there are k bins
Expand Down
4 changes: 2 additions & 2 deletions amcl/src/amcl/pf/pf_kdtree.c
Expand Up @@ -31,8 +31,8 @@
#include <string.h>


#include "pf_vector.h"
#include "pf_kdtree.h"
#include "amcl/pf/pf_vector.h"
#include "amcl/pf/pf_kdtree.h"


// Compare keys to see if they are equal
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/pf/pf_pdf.c
Expand Up @@ -32,7 +32,7 @@
//#include <gsl/gsl_rng.h>
//#include <gsl/gsl_randist.h>

#include "pf_pdf.h"
#include "amcl/pf/pf_pdf.h"

// Random number generator seed value
static unsigned int pf_pdf_seed;
Expand Down
4 changes: 2 additions & 2 deletions amcl/src/amcl/pf/pf_vector.c
Expand Up @@ -30,8 +30,8 @@
//#include <gsl/gsl_eigen.h>
//#include <gsl/gsl_linalg.h>

#include "pf_vector.h"
#include "eig3.h"
#include "amcl/pf/pf_vector.h"
#include "amcl/pf/eig3.h"


// Return a zero vector
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/sensors/amcl_laser.cpp
Expand Up @@ -33,7 +33,7 @@
#include <assert.h>
#include <unistd.h>

#include "amcl_laser.h"
#include "amcl/sensors/amcl_laser.h"

using namespace amcl;

Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/sensors/amcl_odom.cpp
Expand Up @@ -32,7 +32,7 @@
#include <sys/types.h> // required by Darwin
#include <math.h>

#include "amcl_odom.h"
#include "amcl/sensors/amcl_odom.h"

using namespace amcl;

Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/sensors/amcl_sensor.cpp
Expand Up @@ -28,7 +28,7 @@
///////////////////////////////////////////////////////////////////////////


#include "amcl_sensor.h"
#include "amcl/sensors/amcl_sensor.h"

using namespace amcl;

Expand Down
8 changes: 4 additions & 4 deletions amcl/src/amcl_node.cpp
Expand Up @@ -31,10 +31,10 @@
// Signal handling
#include <signal.h>

#include "map/map.h"
#include "pf/pf.h"
#include "sensors/amcl_odom.h"
#include "sensors/amcl_laser.h"
#include "amcl/map/map.h"
#include "amcl/pf/pf.h"
#include "amcl/sensors/amcl_odom.h"
#include "amcl/sensors/amcl_laser.h"

#include "ros/assert.h"

Expand Down
35 changes: 22 additions & 13 deletions base_local_planner/CMakeLists.txt
Expand Up @@ -3,16 +3,22 @@ project(base_local_planner)

find_package(catkin REQUIRED
COMPONENTS
angles
cmake_modules
roscpp
tf
message_generation
costmap_2d
dynamic_reconfigure
geometry_msgs
message_generation
nav_core
nav_msgs
pcl_conversions
costmap_2d
pcl_ros
pluginlib
angles
roscpp
rospy
std_msgs
tf
voxel_grid
)

find_package(Boost REQUIRED
Expand Down Expand Up @@ -56,14 +62,17 @@ catkin_package(
base_local_planner
trajectory_planner_ros
CATKIN_DEPENDS
roscpp
dynamic_reconfigure
message_generation
tf
pluginlib
angles
costmap_2d
dynamic_reconfigure
geometry_msgs
message_runtime
nav_core
angles
nav_msgs
pluginlib
roscpp
std_msgs
tf
)

#uncomment for profiling
Expand Down Expand Up @@ -104,11 +113,12 @@ 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_generate_messages_cpp)
add_dependencies(trajectory_planner_ros ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(trajectory_planner_ros
base_local_planner)

add_executable(point_grid src/point_grid.cpp)
add_dependencies(point_grid ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(point_grid ${catkin_LIBRARIES})

install(TARGETS
Expand Down Expand Up @@ -140,7 +150,6 @@ if(CATKIN_ENABLE_TESTING)
base_local_planner trajectory_planner_ros
)


catkin_add_gtest(line_iterator
test/line_iterator_test.cpp)
endif()
8 changes: 3 additions & 5 deletions base_local_planner/package.xml
Expand Up @@ -19,15 +19,13 @@
<build_depend>cmake_modules</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>rosconsole</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>tf</build_depend>
<build_depend>rospy</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>costmap_2d</build_depend>
<build_depend>voxel_grid</build_depend>
<build_depend>angles</build_depend>
<build_depend>visualization_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>nav_core</build_depend>
<build_depend>pcl_conversions</build_depend>
Expand All @@ -38,21 +36,21 @@

<run_depend>std_msgs</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>rosconsole</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>tf</run_depend>
<run_depend>rospy</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>costmap_2d</run_depend>
<run_depend>voxel_grid</run_depend>
<run_depend>angles</run_depend>
<run_depend>visualization_msgs</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>nav_core</run_depend>
<run_depend>pcl_ros</run_depend>
<run_depend>eigen</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>message_generation</run_depend>
<run_depend>message_runtime</run_depend>

<test_depend>rosunit</test_depend>

<export>
<nav_core plugin="${prefix}/blp_plugin.xml" />
Expand Down
1 change: 1 addition & 0 deletions carrot_planner/CMakeLists.txt
Expand Up @@ -29,6 +29,7 @@ catkin_package(
)

add_library(carrot_planner src/carrot_planner.cpp)
add_dependencies(carrot_planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(carrot_planner
${catkin_LIBRARIES}
)
Expand Down
4 changes: 1 addition & 3 deletions clear_costmap_recovery/CMakeLists.txt
Expand Up @@ -34,6 +34,7 @@ catkin_package(
)

add_library(clear_costmap_recovery src/clear_costmap_recovery.cpp)
add_dependencies(clear_costmap_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(clear_costmap_recovery ${catkin_LIBRARIES})


Expand All @@ -45,9 +46,6 @@ if(CATKIN_ENABLE_TESTING)
# Add the test folder to the include directories
include_directories(test)

include_directories(${GTEST_INCLUDE_DIRS})
link_directories(${GTEST_LIBRARY_DIRS})

# Create targets for test executables
add_rostest_gtest(clear_tester test/clear_tests.launch test/clear_tester.cpp)
target_link_libraries(clear_tester clear_costmap_recovery ${GTEST_LIBRARIES})
Expand Down
2 changes: 2 additions & 0 deletions clear_costmap_recovery/package.xml
Expand Up @@ -30,6 +30,8 @@
<run_depend>pluginlib</run_depend>
<run_depend>eigen</run_depend>

<test_depend>rostest</test_depend>

<export>
<nav_core plugin="${prefix}/ccr_plugin.xml" />
</export>
Expand Down
17 changes: 5 additions & 12 deletions costmap_2d/CMakeLists.txt
Expand Up @@ -62,8 +62,6 @@ generate_dynamic_reconfigure_options(
catkin_package(
INCLUDE_DIRS
include
${EIGEN3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
LIBRARIES costmap_2d layers
CATKIN_DEPENDS
dynamic_reconfigure
Expand Down Expand Up @@ -99,7 +97,7 @@ add_library(costmap_2d
src/footprint.cpp
src/costmap_layer.cpp
)
add_dependencies(costmap_2d geometry_msgs_generate_messages_cpp)
add_dependencies(costmap_2d ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(costmap_2d
${PCL_LIBRARIES}
${Boost_LIBRARIES}
Expand All @@ -113,27 +111,25 @@ add_library(layers
plugins/voxel_layer.cpp
src/observation_buffer.cpp
)
add_dependencies(layers ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
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_generate_messages_cpp)

add_executable(costmap_2d_markers src/costmap_2d_markers.cpp)
add_dependencies(costmap_2d_markers visualization_msgs_generate_messages_cpp)
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_generate_messages_cpp)
add_dependencies(costmap_2d_cloud ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(costmap_2d_cloud
costmap_2d
)

add_executable(costmap_2d_node src/costmap_2d_node.cpp)
add_dependencies(costmap_2d_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(costmap_2d_node
costmap_2d
)
Expand All @@ -146,9 +142,6 @@ if(CATKIN_ENABLE_TESTING)
# Add the test folder to the include directories
include_directories(test)

include_directories(${GTEST_INCLUDE_DIRS})
link_directories(${GTEST_LIBRARY_DIRS})

# Create targets for test executables
add_executable(costmap_tester EXCLUDE_FROM_ALL test/costmap_tester.cpp)
add_dependencies(tests costmap_tester)
Expand Down

0 comments on commit a013a01

Please sign in to comment.