diff --git a/rosbag2_tests/CMakeLists.txt b/rosbag2_tests/CMakeLists.txt index 70aab1ca52..ad1724b068 100644 --- a/rosbag2_tests/CMakeLists.txt +++ b/rosbag2_tests/CMakeLists.txt @@ -20,7 +20,25 @@ endif() find_package(ament_cmake REQUIRED) find_package(ament_index_cpp REQUIRED) +find_package(PkgConfig) +if(PKG_CONFIG_FOUND) + find_package(ros1_bridge REQUIRED) + include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) + include(${ros1_bridge_DIR}/find_ros1_package.cmake) + find_ros1_package(roscpp) + if(NOT ros1_roscpp_FOUND) + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() +else() + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") +endif() + if(BUILD_TESTING) + include(cmake/skip_ros1_tests_if_necessary.cmake) + skip_ros1_tests_if_necessary() + find_package(ament_cmake_gmock REQUIRED) find_package(ament_lint_auto REQUIRED) find_package(rclcpp REQUIRED) @@ -75,28 +93,28 @@ if(BUILD_TESTING) test_msgs) endif() - if(rosbag2_bag_v2_plugins_FOUND) - ament_add_gmock(test_rosbag2_play_rosbag_v2_end_to_end - test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) - if(TARGET test_rosbag2_play_rosbag_v2_end_to_end) - ament_target_dependencies(test_rosbag2_play_rosbag_v2_end_to_end - rosbag2_storage - rclcpp - rosbag2_test_common - std_msgs) - endif() - - ament_add_gmock(test_rosbag2_info_rosbag_v2_end_to_end - test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) - if(TARGET test_rosbag2_info_rosbag_v2_end_to_end) - ament_target_dependencies(test_rosbag2_info_rosbag_v2_end_to_end - rosbag2_storage - rclcpp - rosbag2_test_common - std_msgs) - endif() + ament_add_gmock(test_rosbag2_play_rosbag_v2_end_to_end + test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} + ${SKIP_ROS1_TESTS}) + if(TARGET test_rosbag2_play_rosbag_v2_end_to_end) + ament_target_dependencies(test_rosbag2_play_rosbag_v2_end_to_end + rosbag2_storage + rclcpp + rosbag2_test_common + std_msgs) + endif() + + ament_add_gmock(test_rosbag2_info_rosbag_v2_end_to_end + test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} + ${SKIP_ROS1_TESTS}) + if(TARGET test_rosbag2_info_rosbag_v2_end_to_end) + ament_target_dependencies(test_rosbag2_info_rosbag_v2_end_to_end + rosbag2_storage + rclcpp + rosbag2_test_common + std_msgs) endif() endif() diff --git a/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake b/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake new file mode 100644 index 0000000000..aaec62fe9b --- /dev/null +++ b/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake @@ -0,0 +1,37 @@ +# Copyright 2018, Bosch Software Innovations GmbH. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# Macro to set variable SKIP_ROS1_TESTS if ros1 is not installed +# Some end to end tests rely on the plugin to read rosbags from ROS 1. +# Those tests should be marked with SKIP_ROS1_TESTS and will be skipped if the +# plugin is not available + +macro(skip_ros1_tests_if_necessary) + find_package(PkgConfig) + if(PKG_CONFIG_FOUND) + find_package(ros1_bridge REQUIRED) + include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) + include(${ros1_bridge_DIR}/find_ros1_package.cmake) + find_ros1_package(roscpp) + if(NOT ros1_roscpp_FOUND) + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING + "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() + else() + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING + "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() +endmacro() \ No newline at end of file