Skip to content

Commit

Permalink
Move common cmake rules to modules.
Browse files Browse the repository at this point in the history
Same mech as in `cmake_modules` package.
Issue #139.
  • Loading branch information
vooon committed Aug 28, 2014
1 parent e1091e6 commit ac0fa73
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 30 deletions.
40 changes: 10 additions & 30 deletions mavros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,11 @@ find_package(catkin REQUIRED COMPONENTS
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(Boost REQUIRED COMPONENTS system)
find_package(mavlink REQUIRED)

# add package modules path, not needed in dependend packages
list(INSERT CMAKE_MODULE_PATH 0 "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules")
include(EnableCXX11)
include(MavrosMavlink)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
Expand Down Expand Up @@ -101,18 +105,6 @@ generate_messages(
std_msgs
)

## Select MAVLink dialect
#
# fallback for older mavlink package.
if(NOT DEFINED mavlink_DIALECTS)
list(APPEND mavlink_DIALECTS "ardupilotmega")
list(APPEND mavlink_DIALECTS "pixhawk")
list(APPEND mavlink_DIALECTS "common")
endif()

set(MAVLINK_DIALECT "ardupilotmega" CACHE STRING "MAVLink dialect selector")
set_property(CACHE MAVLINK_DIALECT PROPERTY STRINGS ${mavlink_DIALECTS})


###################################
## catkin specific configuration ##
Expand All @@ -128,6 +120,7 @@ catkin_package(
LIBRARIES mavconn mavros
CATKIN_DEPENDS diagnostic_msgs diagnostic_updater pluginlib roscpp sensor_msgs std_msgs tf geometry_msgs
DEPENDS Boost mavlink
CFG_EXTRAS mavros-extras.cmake
)

###########
Expand All @@ -145,23 +138,6 @@ include_directories(
${mavlink_INCLUDE_DIRS}
)

add_definitions(
-DMAVLINK_DIALECT=${MAVLINK_DIALECT}
)

## Enable C++11 on gcc 4.6 too
# thanks for: http://www.guyrutenberg.com/2014/01/05/enabling-c11-c0x-in-cmake/
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 "${CMAKE_CXX_FLAGS} -std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
else()
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
endif()

## Declare a cpp library
add_library(mavconn
src/mavconn/mavconn_interface.cpp
Expand Down Expand Up @@ -283,6 +259,10 @@ install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)

## Install cmake files (thanks to cmake_modules package)
install(DIRECTORY cmake/Modules
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake
)

#############
## Testing ##
Expand Down
21 changes: 21 additions & 0 deletions mavros/cmake/Modules/EnableCXX11.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
# This module enables C++11 support
#
# It enable C++0x for older compilers like gcc 4.6, or C++11 for newer
# thanks for: http://www.guyrutenberg.com/2014/01/05/enabling-c11-c0x-in-cmake/

include(CheckCXXCompilerFlag)

check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_STD_CXX11)
if (NOT COMPILER_SUPPORTS_STD_CXX11)
check_cxx_compiler_flag("-std=c++0x" COMPILER_SUPPORTS_STD_CXX0X)
endif ()

if (COMPILER_SUPPORTS_STD_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
elseif (COMPILER_SUPPORTS_STD_CXX0X)
set(CMAKE_CXX_FLAGS "${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.")
endif ()

# vim: set ts=2 sw=2 et:
26 changes: 26 additions & 0 deletions mavros/cmake/Modules/MavrosMavlink.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# This module includes MAVLink package and
# define MAVLINK_DIALECT required by mavconn_mavlink.h

find_package(mavlink REQUIRED)

# fallback for older mavlink package.
if(NOT DEFINED mavlink_DIALECTS)
list(APPEND mavlink_DIALECTS "ardupilotmega")
list(APPEND mavlink_DIALECTS "pixhawk")
list(APPEND mavlink_DIALECTS "common")
endif()

# Select MAVLink dialect
set(MAVLINK_DIALECT "ardupilotmega" CACHE STRING "MAVLink dialect selector")
set_property(CACHE MAVLINK_DIALECT PROPERTY STRINGS ${mavlink_DIALECTS})

# TODO: check that selected dialect are known

message(STATUS "Selected MAVLink dialect: ${MAVLINK_DIALECT}")

# define dialect for mavconn_mavlink.h
add_definitions(
-DMAVLINK_DIALECT=${MAVLINK_DIALECT}
)

# vim: set ts=2 sw=2 et:
2 changes: 2 additions & 0 deletions mavros/cmake/mavros-extras.cmake.develspace.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# Prepend cmake modules from source directory to the cmake module path
list(INSERT CMAKE_MODULE_PATH 0 "@CMAKE_CURRENT_SOURCE_DIR@/cmake/Modules")
2 changes: 2 additions & 0 deletions mavros/cmake/mavros-extras.cmake.installspace.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# Prepend the installed cmake modules to the cmake module path
list(INSERT CMAKE_MODULE_PATH 0 "${mavros_DIR}/../../../@CATKIN_PACKAGE_SHARE_DESTINATION@/cmake/Modules")

0 comments on commit ac0fa73

Please sign in to comment.