Skip to content

Commit

Permalink
Fix gazebo catkin warning
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman committed Feb 10, 2017
1 parent f0f24e6 commit af07e21
Showing 1 changed file with 6 additions and 5 deletions.
11 changes: 6 additions & 5 deletions gazebo_ros_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,18 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
control_toolbox
controller_manager
hardware_interface
hardware_interface
transmission_interface
pluginlib
joint_limits_interface
urdf
angles
)

# Depend on system install of Gazebo
find_package(gazebo REQUIRED)
# Depend on system install of Gazebo and SDFormat
find_package(GAZEBO REQUIRED)
find_package(SDFormat REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")

catkin_package(
Expand All @@ -33,7 +35,7 @@ catkin_package(
angles
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME} default_robot_hw_sim
DEPENDS gazebo
DEPENDS GAZEBO
)

link_directories(
Expand Down Expand Up @@ -67,4 +69,3 @@ install(DIRECTORY include/${PROJECT_NAME}/
install(FILES robot_hw_sim_plugins.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

0 comments on commit af07e21

Please sign in to comment.