diff --git a/CMakeLists.txt b/CMakeLists.txt index d4826197..7823c5ce 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,7 +4,8 @@ project(dynamic_reconfigure) find_package(catkin REQUIRED COMPONENTS message_generation roscpp std_msgs) find_package(Boost REQUIRED COMPONENTS system thread chrono) -include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) +include_directories(include) +include_directories(SYSTEM ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) catkin_python_setup() diff --git a/cmake/dynamic_reconfigure-macros.cmake b/cmake/dynamic_reconfigure-macros.cmake index 67a6ba9b..45095b92 100644 --- a/cmake/dynamic_reconfigure-macros.cmake +++ b/cmake/dynamic_reconfigure-macros.cmake @@ -114,7 +114,8 @@ macro(dynreconf_called) endif() # make sure we can find generated messages and that they overlay all other includes - include_directories(BEFORE ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}) + # Use system to skip warnings from these includes + include_directories(SYSTEM BEFORE ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}) # pass the include directory to catkin_package() list(APPEND ${PROJECT_NAME}_INCLUDE_DIRS ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}) # ensure that the folder exists