Skip to content

Commit

Permalink
enable compiler warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Mar 2, 2016
1 parent 05e7bd4 commit 3cf904d
Show file tree
Hide file tree
Showing 12 changed files with 51 additions and 1 deletion.
4 changes: 4 additions & 0 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(roscpp)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS
cpp_common message_generation rosconsole roscpp_serialization roscpp_traits rosgraph_msgs rostime std_msgs xmlrpcpp
)
Expand Down
5 changes: 5 additions & 0 deletions test/test_rosbag/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
cmake_minimum_required(VERSION 2.8.3)

project(test_rosbag)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS message_generation rosbag rosconsole roscpp rosgraph_msgs rostest rosunit topic_tools xmlrpcpp)

if(CATKIN_ENABLE_TESTING)
Expand Down
4 changes: 4 additions & 0 deletions test/test_roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)

project(test_roscpp)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS
message_generation roscpp rostest rosunit std_srvs
)
Expand Down
5 changes: 5 additions & 0 deletions tools/rosbag/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosbag)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS rosbag_storage rosconsole roscpp topic_tools xmlrpcpp)
find_package(Boost REQUIRED COMPONENTS date_time regex program_options filesystem)
find_package(BZip2 REQUIRED)
Expand Down
4 changes: 4 additions & 0 deletions tools/rosbag_storage/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)

project(rosbag_storage)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(console_bridge REQUIRED)
find_package(catkin REQUIRED COMPONENTS cpp_common roscpp_serialization roscpp_traits rostime roslz4)
find_package(Boost REQUIRED COMPONENTS date_time filesystem program_options regex)
Expand Down
4 changes: 4 additions & 0 deletions tools/rosconsole/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosconsole)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS cpp_common rostime rosunit)

find_package(Boost COMPONENTS regex system thread)
Expand Down
5 changes: 5 additions & 0 deletions tools/rosout/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosout)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS roscpp)

catkin_package()
Expand Down
2 changes: 1 addition & 1 deletion tools/rostest/cmake/rostest-extras.cmake.em
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ function(add_rostest file)
endforeach()
set(_testname "${_testname}${_ext}")
endif()

string(REPLACE "/" "_" _testname ${_testname})

get_filename_component(_output_name ${_testname} NAME_WE)
Expand Down
5 changes: 5 additions & 0 deletions tools/topic_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(topic_tools)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin COMPONENTS cpp_common message_generation rosconsole roscpp rostime std_msgs xmlrpcpp)

include_directories(include)
Expand Down
5 changes: 5 additions & 0 deletions utilities/message_filters/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(message_filters)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS roscpp xmlrpcpp rosconsole)
catkin_package(
INCLUDE_DIRS include
Expand Down
4 changes: 4 additions & 0 deletions utilities/roslz4/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@ cmake_minimum_required(VERSION 2.8.3)

project(roslz4)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED)

find_path(lz4_INCLUDE_DIRS NAMES lz4.h)
Expand Down
5 changes: 5 additions & 0 deletions utilities/xmlrpcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(xmlrpcpp)

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS cpp_common)
catkin_package(
INCLUDE_DIRS include
Expand Down

8 comments on commit 3cf904d

@mikepurvis
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wouldn't this be better done as, eg:

set_property(DIRECTORY . APPEND PROPERTY COMPILE_OPTIONS -Wall -Wextra)

Then you're not polluting the build flags for the rest of the workspace.

@dirk-thomas
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point. I tend to forget that some users are still building without isolation.

@mikepurvis
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are you using catkin_make_isolated or catkin build? Or do you just typically build a single repo at a time?

@wjwwood
Copy link
Member

@wjwwood wjwwood commented on 3cf904d Apr 5, 2016

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can't speak for @dirk-thomas, but I pretty much always use catkin_make_isolated, just in case there is a plain cmake package in the mix. We might use catkin build from time to time, but until we get the linger issues with it addressed (which we're working on), we tend to use catkin_make_isolated because that's what more people are using at the moment.

@mikepurvis
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Huh, interesting. Has there been an official change of recommendation? Noting:

2000 results: https://www.google.ca/search?q=%22catkin_make_isolated%22
13000 results: https://www.google.ca/search?q=%22catkin_make%22

And that the official tutorials all still recommend catkin_make. I would guess that the vast majority of users who have not switched to catkin_tools are "still" building without isolation.

@wjwwood
Copy link
Member

@wjwwood wjwwood commented on 3cf904d Apr 5, 2016

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I didn't mean to imply that more people used catkin_make_isolated in general, just that more people use catkin_make_isolated over catkin build. I'm certain many people use catkin_make, and so we try to support it, but we often have non-homogeneous workspaces where catkin_make is just not convenient for us to use in everyday tasks.

@dirk-thomas
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have created #785 to address this.

@mikepurvis As William mentioned I also often use catkin_make_isolated since it allows to have plain CMake packages in the workspace. I haven't used catkin_tools.

@mikepurvis
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

catkin_tools is sweet. Definitely give it a try.

Please sign in to comment.