Skip to content

Commit

Permalink
Revert catkin warnings to fix regressions (problems with catkin -lpth…
Browse files Browse the repository at this point in the history
…reads errors)

For reference and reasons, please check:
https://discourse.ros.org/t/need-to-sync-new-release-of-rqt-topic-indigo-jade-kinetic/1410/4

* Revert "Fix gazebo catkin warning, cleanup CMakeLists (#537)"
This reverts commit 5a0305f.

* Revert "Fix gazebo and sdformat catkin warnings"
This reverts commit 11f95d2.
  • Loading branch information
j-rivero authored Mar 3, 2017
1 parent a89c2ad commit 6c9786d
Show file tree
Hide file tree
Showing 3 changed files with 93 additions and 115 deletions.
152 changes: 67 additions & 85 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,26 +1,24 @@
cmake_minimum_required(VERSION 2.8.3)
project(gazebo_plugins)

option(ENABLE_DISPLAY_TESTS "Enable the building of tests that requires a display" OFF)

find_package(catkin REQUIRED COMPONENTS
message_generation
gazebo_msgs
roscpp
rospy
nodelet
angles
std_srvs
geometry_msgs
sensor_msgs
nav_msgs
urdf
tf
tf2_ros
dynamic_reconfigure
rosgraph_msgs
trajectory_msgs
image_transport
message_generation
gazebo_msgs
roscpp
rospy
nodelet
angles
std_srvs
geometry_msgs
sensor_msgs
nav_msgs
urdf
tf
tf2_ros
dynamic_reconfigure
rosgraph_msgs
trajectory_msgs
image_transport
rosconsole
cv_bridge
polled_camera
Expand All @@ -40,8 +38,7 @@ else()
endif()

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

Expand Down Expand Up @@ -77,6 +74,8 @@ 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 All @@ -87,60 +86,60 @@ endif()

catkin_package(
INCLUDE_DIRS include
LIBRARIES
vision_reconfigure
gazebo_ros_utils
gazebo_ros_camera_utils
gazebo_ros_camera
gazebo_ros_multicamera
gazebo_ros_depth_camera
gazebo_ros_openni_kinect
gazebo_ros_gpu_laser
gazebo_ros_laser
gazebo_ros_block_laser
gazebo_ros_p3d
gazebo_ros_imu
gazebo_ros_f3d
LIBRARIES
vision_reconfigure
gazebo_ros_utils
gazebo_ros_camera_utils
gazebo_ros_camera
gazebo_ros_multicamera
gazebo_ros_depth_camera
gazebo_ros_openni_kinect
gazebo_ros_gpu_laser
gazebo_ros_laser
gazebo_ros_block_laser
gazebo_ros_p3d
gazebo_ros_imu
gazebo_ros_f3d
gazebo_ros_ft_sensor
gazebo_ros_bumper
gazebo_ros_template
gazebo_ros_projector
gazebo_ros_prosilica
gazebo_ros_force
gazebo_ros_joint_trajectory
gazebo_ros_joint_state_publisher
gazebo_ros_bumper
gazebo_ros_template
gazebo_ros_projector
gazebo_ros_prosilica
gazebo_ros_force
gazebo_ros_joint_trajectory
gazebo_ros_joint_state_publisher
gazebo_ros_joint_pose_trajectory
gazebo_ros_diff_drive
gazebo_ros_tricycle_drive
gazebo_ros_skid_steer_drive
gazebo_ros_video
gazebo_ros_planar_move
gazebo_ros_vacuum_gripper

CATKIN_DEPENDS
message_generation
gazebo_msgs
roscpp
rospy
nodelet
angles
std_srvs
geometry_msgs
sensor_msgs
nav_msgs
urdf
tf
CATKIN_DEPENDS
message_generation
gazebo_msgs
roscpp
rospy
nodelet
angles
std_srvs
geometry_msgs
sensor_msgs
nav_msgs
urdf
tf
tf2_ros
dynamic_reconfigure
rosgraph_msgs
trajectory_msgs
image_transport
dynamic_reconfigure
rosgraph_msgs
trajectory_msgs
image_transport
rosconsole
camera_info_manager
std_msgs
DEPENDS
GAZEBO
SDFormat
DEPENDS
gazebo
SDF
)
add_dependencies(${PROJECT_NAME}_gencfg ${catkin_EXPORTED_TARGETS})

Expand Down Expand Up @@ -289,9 +288,9 @@ target_link_libraries(gazebo_ros_vacuum_gripper ${GAZEBO_LIBRARIES} ${catkin_LIB
add_library(gazebo_ros_template src/gazebo_ros_template.cpp)
target_link_libraries(gazebo_ros_template ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(TARGETS
hokuyo_node
vision_reconfigure
install(TARGETS
hokuyo_node
vision_reconfigure
camera_synchronizer
gazebo_ros_utils
gazebo_ros_camera_utils
Expand Down Expand Up @@ -322,7 +321,7 @@ install(TARGETS
gazebo_ros_video
gazebo_ros_planar_move
gazebo_ros_vacuum_gripper
pub_joint_trajectory_test
pub_joint_trajectory_test
gazebo_ros_gpu_laser
gazebo_ros_range
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
Expand Down Expand Up @@ -361,28 +360,11 @@ install(DIRECTORY test
)

# Tests
# These need to be run with -j1 flag because gazebo can't be run
# in parallel.
if (CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest_gtest(set_model_state-test
test/set_model_state_test/set_model_state_test.test
test/set_model_state_test/set_model_state_test.test
test/set_model_state_test/set_model_state_test.cpp)
add_rostest(test/range/range_plugin.test)
target_link_libraries(set_model_state-test ${catkin_LIBRARIES})

if (ENABLE_DISPLAY_TESTS)
add_rostest_gtest(depth_camera-test
test/camera/depth_camera.test
test/camera/depth_camera.cpp)
target_link_libraries(depth_camera-test ${catkin_LIBRARIES})
add_rostest_gtest(multicamera-test
test/camera/multicamera.test
test/camera/multicamera.cpp)
target_link_libraries(multicamera-test ${catkin_LIBRARIES})
add_rostest_gtest(camera-test
test/camera/camera.test
test/camera/camera.cpp)
target_link_libraries(camera-test ${catkin_LIBRARIES})
endif()
endif()
33 changes: 17 additions & 16 deletions gazebo_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,20 +36,21 @@ 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 @@ -61,8 +62,7 @@ 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,4 +112,5 @@ install(PROGRAMS scripts/gazebo
# Install Gazebo launch files
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)
)

23 changes: 9 additions & 14 deletions gazebo_ros_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,9 @@ 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 @@ -33,14 +31,9 @@ catkin_package(
joint_limits_interface
urdf
angles
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
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME} default_robot_hw_sim
DEPENDS gazebo
)

link_directories(
Expand All @@ -53,6 +46,7 @@ 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 @@ -64,12 +58,13 @@ 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 6c9786d

Please sign in to comment.