From 686e31f0eaf136511e674b1895d9941c6016bed4 Mon Sep 17 00:00:00 2001 From: Dave Coleman Date: Fri, 10 Feb 2017 21:57:13 +0530 Subject: [PATCH] Fix gazebo catkin warning, cleanup CMakeLists --- gazebo_plugins/CMakeLists.txt | 2 -- gazebo_ros/CMakeLists.txt | 33 +++++++++++++++---------------- gazebo_ros_control/CMakeLists.txt | 32 ++++++++++++++++-------------- 3 files changed, 33 insertions(+), 34 deletions(-) diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index 29e14bc16..90235c249 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -75,8 +75,6 @@ link_directories( ${catkin_LIBRARY_DIRS} ) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") - if (NOT GAZEBO_VERSION VERSION_LESS 6.0) catkin_package( INCLUDE_DIRS include LIBRARIES gazebo_ros_elevator) endif() diff --git a/gazebo_ros/CMakeLists.txt b/gazebo_ros/CMakeLists.txt index c23ee1595..66222a070 100644 --- a/gazebo_ros/CMakeLists.txt +++ b/gazebo_ros/CMakeLists.txt @@ -36,21 +36,20 @@ generate_dynamic_reconfigure_options(cfg/Physics.cfg) catkin_package( LIBRARIES - gazebo_ros_api_plugin - gazebo_ros_paths_plugin + gazebo_ros_api_plugin + gazebo_ros_paths_plugin CATKIN_DEPENDS - roslib - roscpp - geometry_msgs - std_srvs - tf - rosgraph_msgs - dynamic_reconfigure - message_generation - std_msgs - gazebo_msgs - + roslib + roscpp + geometry_msgs + std_srvs + tf + rosgraph_msgs + dynamic_reconfigure + message_generation + std_msgs + gazebo_msgs DEPENDS TinyXML @@ -62,7 +61,8 @@ include_directories( ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS} ${SDFormat_INCLUDE_DIRS} - ${TinyXML_INCLUDE_DIRS}) + ${TinyXML_INCLUDE_DIRS} +) link_directories(${catkin_LIBRARY_DIRS}) @@ -94,7 +94,7 @@ target_link_libraries(gazebo_ros_paths_plugin ${GAZEBO_LIBRARIES} ${SDFormat_LIB # Install Gazebo System Plugins install(TARGETS gazebo_ros_api_plugin gazebo_ros_paths_plugin LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ) +) # Install Gazebo Scripts install(PROGRAMS scripts/gazebo @@ -112,5 +112,4 @@ install(PROGRAMS scripts/gazebo # Install Gazebo launch files install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - ) - +) diff --git a/gazebo_ros_control/CMakeLists.txt b/gazebo_ros_control/CMakeLists.txt index 79baf9e35..5cdad35b1 100644 --- a/gazebo_ros_control/CMakeLists.txt +++ b/gazebo_ros_control/CMakeLists.txt @@ -16,9 +16,11 @@ find_package(catkin REQUIRED COMPONENTS ) # Depend on system install of Gazebo -find_package(gazebo REQUIRED) +find_package(GAZEBO REQUIRED) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") +find_package(Boost REQUIRED COMPONENTS thread) + catkin_package( CATKIN_DEPENDS roscpp @@ -31,14 +33,11 @@ catkin_package( joint_limits_interface urdf angles - INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} default_robot_hw_sim - DEPENDS gazebo -) - -link_directories( - ${GAZEBO_LIBRARY_DIRS} - ${catkin_LIBRARY_DIRS} + INCLUDE_DIRS + include + LIBRARIES + ${PROJECT_NAME} + default_robot_hw_sim ) include_directories(include @@ -46,9 +45,13 @@ include_directories(include ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS} ) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") -## Libraries +link_directories( + ${GAZEBO_LIBRARY_DIRS} + ${catkin_LIBRARY_DIRS} +) + +## libraries add_library(${PROJECT_NAME} src/gazebo_ros_control_plugin.cpp) target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES}) @@ -58,13 +61,12 @@ target_link_libraries(default_robot_hw_sim ${catkin_LIBRARIES} ${GAZEBO_LIBRARIE ## Install install(TARGETS ${PROJECT_NAME} default_robot_hw_sim LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ) +) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - ) +) install(FILES robot_hw_sim_plugins.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - +)