2016-09-19 15:08:14 -03:00
|
|
|
cmake_minimum_required(VERSION 2.8.3)
|
|
|
|
project(rosbuzz)
|
2016-10-10 21:22:17 -03:00
|
|
|
|
|
|
|
if(UNIX)
|
|
|
|
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=gnu++11")
|
|
|
|
endif()
|
|
|
|
|
2016-09-19 15:08:14 -03:00
|
|
|
## Find catkin macros and libraries
|
|
|
|
find_package(catkin REQUIRED COMPONENTS
|
|
|
|
roscpp
|
|
|
|
std_msgs
|
2016-12-05 19:20:53 -04:00
|
|
|
mavros_msgs
|
2016-10-02 18:40:01 -03:00
|
|
|
sensor_msgs
|
2016-09-19 15:08:14 -03:00
|
|
|
)
|
|
|
|
|
|
|
|
###################################
|
|
|
|
## catkin specific configuration ##
|
|
|
|
###################################
|
2016-10-08 19:09:32 -03:00
|
|
|
|
2016-09-19 15:08:14 -03:00
|
|
|
catkin_package(
|
2016-10-10 21:22:17 -03:00
|
|
|
INCLUDE_DIRS include
|
|
|
|
# LIBRARIES xbee_ros_node
|
|
|
|
CATKIN_DEPENDS roscpp std_msgs mavros_msgs sensor_msgs
|
|
|
|
# DEPENDS system_lib
|
2016-09-19 15:08:14 -03:00
|
|
|
)
|
2016-10-10 21:22:17 -03:00
|
|
|
|
2016-09-19 15:08:14 -03:00
|
|
|
###########
|
|
|
|
## Build ##
|
|
|
|
###########
|
|
|
|
|
|
|
|
include_directories(
|
2016-10-10 21:22:17 -03:00
|
|
|
include ${rosbuzz_INCLUDE_DIRS}
|
2016-09-19 15:08:14 -03:00
|
|
|
${catkin_INCLUDE_DIRS}
|
|
|
|
)
|
|
|
|
|
2016-10-08 19:09:32 -03:00
|
|
|
# Executables
|
2016-09-19 15:08:14 -03:00
|
|
|
add_executable(rosbuzz_node src/rosbuzz.cpp
|
2016-10-10 21:22:17 -03:00
|
|
|
src/roscontroller.cpp
|
2016-09-19 15:08:14 -03:00
|
|
|
src/buzz_utility.cpp
|
|
|
|
src/buzzuav_closures.cpp
|
|
|
|
src/uav_utility.cpp)
|
|
|
|
target_link_libraries(rosbuzz_node ${catkin_LIBRARIES} /usr/local/lib/libbuzz.so /usr/local/lib/libbuzzdbg.so -lpthread)
|
|
|
|
|
2016-10-08 19:09:32 -03:00
|
|
|
# Executables and libraries for installation to do
|
2016-09-19 15:08:14 -03:00
|
|
|
install(TARGETS rosbuzz_node
|
|
|
|
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
|
|
|
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
|
|
|
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
|
|
|
)
|
|
|
|
|
2016-10-09 20:58:50 -03:00
|
|
|
find_package(catkin REQUIRED COMPONENTS roslaunch)
|
|
|
|
roslaunch_add_file_check(launch)
|