From 1dcbafa8b94b562ca8444bd3079c6042e7bc690b Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 5 Feb 2020 15:17:57 -0800 Subject: [PATCH 1/2] use target include directories Signed-off-by: Karsten Knese --- gazebo_plugins/CMakeLists.txt | 33 ++++++++++++++++++++++----------- 1 file changed, 22 insertions(+), 11 deletions(-) diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index 1ae4e78d3..b5dfea084 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -29,23 +29,13 @@ find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(trajectory_msgs REQUIRED) -include_directories(include - ${gazebo_dev_INCLUDE_DIRS} - ${gazebo_ros_INCLUDE_DIRS} - ${geometry_msgs_INCLUDE_DIRS} - ${image_transport_INCLUDE_DIRS} - ${cv_bridge_INCLUDE_DIRS} - ${nav_msgs_INCLUDE_DIRS} - ${sensor_msgs_INCLUDE_DIRS} - ${tf2_ros_INCLUDE_DIRS} - ${tf2_INCLUDE_DIRS} -) link_directories(${gazebo_dev_LIBRARY_DIRS}) # gazebo_ros_joint_state_publisher add_library(gazebo_ros_joint_state_publisher SHARED src/gazebo_ros_joint_state_publisher.cpp ) +target_include_directories(gazebo_ros_joint_state_publisher PUBLIC include) ament_target_dependencies(gazebo_ros_joint_state_publisher "gazebo_dev" "gazebo_ros" @@ -58,6 +48,7 @@ ament_export_libraries(gazebo_ros_joint_state_publisher) add_library(gazebo_ros_diff_drive SHARED src/gazebo_ros_diff_drive.cpp ) +target_include_directories(gazebo_ros_diff_drive PUBLIC include) ament_target_dependencies(gazebo_ros_diff_drive "gazebo_dev" "gazebo_ros" @@ -74,6 +65,7 @@ ament_export_libraries(gazebo_ros_diff_drive) add_library(gazebo_ros_force SHARED src/gazebo_ros_force.cpp ) +target_include_directories(gazebo_ros_force PUBLIC include) ament_target_dependencies(gazebo_ros_force "gazebo_dev" "gazebo_ros" @@ -86,6 +78,7 @@ ament_export_libraries(gazebo_ros_force) add_library(gazebo_ros_template SHARED src/gazebo_ros_template.cpp ) +target_include_directories(gazebo_ros_template PUBLIC include) ament_target_dependencies(gazebo_ros_template "gazebo_dev" "gazebo_ros" @@ -97,6 +90,7 @@ ament_export_libraries(gazebo_ros_template) add_library(multi_camera_plugin SHARED src/multi_camera_plugin.cpp ) +target_include_directories(multi_camera_plugin PUBLIC include) ament_target_dependencies(multi_camera_plugin "gazebo_dev" ) @@ -111,6 +105,7 @@ target_compile_definitions(multi_camera_plugin add_library(gazebo_ros_camera SHARED src/gazebo_ros_camera.cpp ) +target_include_directories(gazebo_ros_camera PUBLIC include) ament_target_dependencies(gazebo_ros_camera "camera_info_manager" "gazebo_dev" @@ -131,6 +126,7 @@ ament_export_libraries(gazebo_ros_camera) add_library(gazebo_ros_imu_sensor SHARED src/gazebo_ros_imu_sensor.cpp ) +target_include_directories(gazebo_ros_imu_sensor PUBLIC include) ament_target_dependencies(gazebo_ros_imu_sensor "gazebo_ros" "sensor_msgs" @@ -146,6 +142,7 @@ ament_export_libraries(gazebo_ros_imu_sensor) add_library(gazebo_ros_gps_sensor SHARED src/gazebo_ros_gps_sensor.cpp ) +target_include_directories(gazebo_ros_gps_sensor PUBLIC include) ament_target_dependencies(gazebo_ros_gps_sensor "gazebo_ros" "sensor_msgs" @@ -157,6 +154,7 @@ ament_export_libraries(gazebo_ros_gps_sensor) add_library(gazebo_ros_ray_sensor SHARED src/gazebo_ros_ray_sensor.cpp ) +target_include_directories(gazebo_ros_ray_sensor PUBLIC include) ament_target_dependencies(gazebo_ros_ray_sensor "gazebo_ros" "sensor_msgs" @@ -166,6 +164,7 @@ ament_export_libraries(gazebo_ros_ray_sensor) add_library(gazebo_ros_p3d SHARED src/gazebo_ros_p3d.cpp ) +target_include_directories(gazebo_ros_p3d PUBLIC include) ament_target_dependencies(gazebo_ros_p3d "gazebo_ros" "gazebo_dev" @@ -182,6 +181,7 @@ ament_export_libraries(gazebo_ros_p3d) add_library(gazebo_ros_tricycle_drive SHARED src/gazebo_ros_tricycle_drive.cpp ) +target_include_directories(gazebo_ros_tricycle_drive PUBLIC include) ament_target_dependencies(gazebo_ros_tricycle_drive "gazebo_ros" "geometry_msgs" @@ -198,6 +198,7 @@ ament_export_libraries(gazebo_ros_tricycle_drive) add_library(gazebo_ros_video SHARED src/gazebo_ros_video.cpp ) +target_include_directories(gazebo_ros_video PUBLIC include) ament_target_dependencies(gazebo_ros_video "gazebo_ros" "sensor_msgs" @@ -209,6 +210,7 @@ ament_export_libraries(gazebo_ros_video) add_library(gazebo_ros_ft_sensor SHARED src/gazebo_ros_ft_sensor.cpp ) +target_include_directories(gazebo_ros_ft_sensor PUBLIC include) ament_target_dependencies(gazebo_ros_ft_sensor "gazebo_ros" "gazebo_dev" @@ -221,6 +223,7 @@ ament_export_libraries(gazebo_ros_ft_sensor) add_library(gazebo_ros_bumper SHARED src/gazebo_ros_bumper.cpp ) +target_include_directories(gazebo_ros_bumper PUBLIC include) ament_target_dependencies(gazebo_ros_bumper "gazebo_ros" "gazebo_msgs" @@ -232,6 +235,7 @@ ament_export_libraries(gazebo_ros_bumper) add_library(gazebo_ros_harness SHARED src/gazebo_ros_harness.cpp ) +target_include_directories(gazebo_ros_harness PUBLIC include) ament_target_dependencies(gazebo_ros_harness "gazebo_dev" "gazebo_ros" @@ -247,6 +251,7 @@ ament_export_libraries(gazebo_ros_harness) add_library(gazebo_ros_hand_of_god SHARED src/gazebo_ros_hand_of_god.cpp ) +target_include_directories(gazebo_ros_hand_of_god PUBLIC include) ament_target_dependencies(gazebo_ros_hand_of_god "gazebo_ros" "gazebo_dev" @@ -261,6 +266,7 @@ ament_export_libraries(gazebo_ros_hand_of_god) add_library(gazebo_ros_ackermann_drive SHARED src/gazebo_ros_ackermann_drive.cpp ) +target_include_directories(gazebo_ros_ackermann_drive PUBLIC include) ament_target_dependencies(gazebo_ros_ackermann_drive "gazebo_dev" "gazebo_ros" @@ -277,6 +283,7 @@ ament_export_libraries(gazebo_ros_ackermann_drive) add_library(gazebo_ros_elevator SHARED src/gazebo_ros_elevator.cpp ) +target_include_directories(gazebo_ros_elevator PUBLIC include) ament_target_dependencies(gazebo_ros_elevator "gazebo_ros" "gazebo_dev" @@ -292,6 +299,7 @@ ament_export_libraries(gazebo_ros_elevator) add_library(gazebo_ros_vacuum_gripper SHARED src/gazebo_ros_vacuum_gripper.cpp ) +target_include_directories(gazebo_ros_vacuum_gripper PUBLIC include) ament_target_dependencies(gazebo_ros_vacuum_gripper "gazebo_ros" "gazebo_dev" @@ -305,6 +313,7 @@ ament_export_libraries(gazebo_ros_vacuum_gripper) add_library(gazebo_ros_joint_pose_trajectory SHARED src/gazebo_ros_joint_pose_trajectory.cpp ) +target_include_directories(gazebo_ros_joint_pose_trajectory PUBLIC include) ament_target_dependencies(gazebo_ros_joint_pose_trajectory "gazebo_dev" "gazebo_ros" @@ -317,6 +326,7 @@ ament_export_libraries(gazebo_ros_joint_pose_trajectory) add_library(gazebo_ros_planar_move SHARED src/gazebo_ros_planar_move.cpp ) +target_include_directories(gazebo_ros_planar_move PUBLIC include) ament_target_dependencies(gazebo_ros_planar_move "gazebo_dev" "gazebo_ros" @@ -332,6 +342,7 @@ ament_export_libraries(gazebo_ros_planar_move) add_library(gazebo_ros_projector SHARED src/gazebo_ros_projector.cpp ) +target_include_directories(gazebo_ros_projector PUBLIC include) ament_target_dependencies(gazebo_ros_projector "gazebo_ros" "gazebo_dev" From 8072b656e042c8f9c9ca7aaffd70687f2296822c Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 18 Jun 2020 16:07:15 -0700 Subject: [PATCH 2/2] add image_transport Signed-off-by: Louise Poubel --- gazebo_plugins/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index b5dfea084..aa46f5f4d 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -201,6 +201,7 @@ add_library(gazebo_ros_video SHARED target_include_directories(gazebo_ros_video PUBLIC include) ament_target_dependencies(gazebo_ros_video "gazebo_ros" + "image_transport" "sensor_msgs" "cv_bridge" )