Skip to content

Commit

Permalink
clang-tidy code need c++11
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Apr 22, 2019
1 parent 4c4caef commit f1a8c68
Showing 1 changed file with 16 additions and 0 deletions.
16 changes: 16 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,22 @@
cmake_minimum_required(VERSION 2.8.3)
project(opencv_apps)

## https://stackoverflow.com/questions/10984442/how-to-detect-c11-support-of-a-compiler-with-cmake
if(CMAKE_COMPILER_IS_GNUCXX)
execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION)
if (GCC_VERSION VERSION_GREATER 4.7 OR GCC_VERSION VERSION_EQUAL 4.7)
message(STATUS "C++11 activated.")
add_definitions("-std=gnu++11")
elseif(GCC_VERSION VERSION_GREATER 4.3 OR GCC_VERSION VERSION_EQUAL 4.3)
message(WARNING "C++0x activated. If you get any errors update to a compiler which fully supports C++11")
add_definitions("-std=gnu++0x")
else ()
message(FATAL_ERROR "C++11 needed. Therefore a gcc compiler with a version higher than 4.3 is needed.")
endif()
else(CMAKE_COMPILER_IS_GNUCXX)
add_definitions("-std=c++0x")
endif(CMAKE_COMPILER_IS_GNUCXX)

find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp sensor_msgs std_msgs std_srvs)

find_package(OpenCV REQUIRED)
Expand Down

0 comments on commit f1a8c68

Please sign in to comment.