Skip to content

Commit

Permalink
Fix gazebo catkin warning, cleanup CMakeLists
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman committed Feb 16, 2017
1 parent de823c0 commit 8c52185
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 28 deletions.
2 changes: 0 additions & 2 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
33 changes: 16 additions & 17 deletions gazebo_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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})

Expand Down Expand Up @@ -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
Expand All @@ -112,5 +112,4 @@ install(PROGRAMS scripts/gazebo
# Install Gazebo launch files
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)

)
23 changes: 14 additions & 9 deletions gazebo_ros_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -31,9 +33,14 @@ catkin_package(
joint_limits_interface
urdf
angles
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME} default_robot_hw_sim
DEPENDS gazebo
DEPENDS
#GAZEBO # Re-enable after issue resolved:
# https://bitbucket.org/osrf/gazebo/issues/2198/gazebo7-linking-error-with-cmake-catkin
INCLUDE_DIRS
include
LIBRARIES
${PROJECT_NAME}
default_robot_hw_sim
)

link_directories(
Expand All @@ -46,7 +53,6 @@ include_directories(include
${catkin_INCLUDE_DIRS}
${GAZEBO_INCLUDE_DIRS}
)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")

## Libraries
add_library(${PROJECT_NAME} src/gazebo_ros_control_plugin.cpp)
Expand All @@ -58,13 +64,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}
)

)

0 comments on commit 8c52185

Please sign in to comment.