Skip to content
Snippets Groups Projects
Commit ed553a68 authored by Jennifer Buehler's avatar Jennifer Buehler
Browse files

Merge branch 'jacknlliu-fix-c11-error'

parents 3cb9e937 b1f902ec
No related branches found
No related tags found
No related merge requests found
......@@ -31,12 +31,23 @@ catkin_package(
INCLUDE_DIRS include
LIBRARIES gazebo_grasp_fix
CATKIN_DEPENDS gazebo_ros geometry_msgs roscpp std_msgs
DEPENDS gazebo
DEPENDS gazebo_ros
)
###########
## Build ##
###########
# check c++11 / c++0x
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "-std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "-std=c++0x")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ")
endif()
## Specify additional locations of header files
## Your package locations should be listed before other locations
......
......@@ -40,12 +40,23 @@ catkin_package(
LIBRARIES gazebo_state_plugins gazebo_map_publisher
CATKIN_DEPENDS geometry_msgs roscpp shape_msgs std_msgs nav_msgs gazebo_world_plugin_loader
gazebo_ros object_msgs object_msgs_tools eigen_conversions
DEPENDS gazebo
DEPENDS gazebo_ros
)
###########
## Build ##
###########
# check c++11 / c++0x
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "-std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "-std=c++0x")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ")
endif()
## Specify additional locations of header files
## Your package locations should be listed before other locations
......
......@@ -64,7 +64,7 @@ catkin_package(
INCLUDE_DIRS include
LIBRARIES gazebo_test_tools
CATKIN_DEPENDS object_msgs gazebo_ros geometry_msgs roscpp std_msgs message_runtime
DEPENDS gazebo
DEPENDS gazebo_ros
)
###########
......
......@@ -5,7 +5,7 @@ project(gazebo_world_plugin_loader)
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(
catkin
catkin
REQUIRED COMPONENTS
roscpp
gazebo_ros
......@@ -31,12 +31,24 @@ catkin_package(
INCLUDE_DIRS include
LIBRARIES gazebo_world_plugin_loader
CATKIN_DEPENDS roscpp gazebo_ros
DEPENDS gazebo
DEPENDS gazebo_ros
)
###########
## Build ##
###########
# check c++11 / c++0x
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "-std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "-std=c++0x")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ")
endif()
## Specify additional locations of header files
## Your package locations should be listed before other locations
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment