Skip to content

Commit

Permalink
Use ROS isolated version of tests
Browse files Browse the repository at this point in the history
  • Loading branch information
Pete Baughman committed Jun 14, 2019
1 parent d630f8e commit 84b05a1
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 3 deletions.
3 changes: 2 additions & 1 deletion rosbag2_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ if(BUILD_TESTING)
skip_ros1_tests_if_necessary()

find_package(ament_cmake_gmock REQUIRED)
find_package(ament_cmake_ros REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
Expand All @@ -36,7 +37,7 @@ if(BUILD_TESTING)

ament_lint_auto_find_test_dependencies()

ament_add_gmock(test_rosbag2_record_end_to_end
ament_add_ros_isolated_gmock(test_rosbag2_record_end_to_end
test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_rosbag2_record_end_to_end)
Expand Down
1 change: 1 addition & 0 deletions rosbag2_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<depend>ament_index_cpp</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>rosbag2_storage_default_plugins</test_depend>
Expand Down
5 changes: 3 additions & 2 deletions rosbag2_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ ament_export_dependencies(rosbag2)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_cmake_ros REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(test_msgs REQUIRED)
find_package(rosbag2_test_common REQUIRED)
Expand All @@ -100,15 +101,15 @@ if(BUILD_TESTING)
ament_target_dependencies(test_record test_msgs rosbag2_test_common)
endif()

ament_add_gmock(test_record_all
ament_add_ros_isolated_gmock(test_record_all
test/rosbag2_transport/test_record_all.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_record_all)
target_link_libraries(test_record_all rosbag2_transport)
ament_target_dependencies(test_record_all test_msgs rosbag2_test_common)
endif()

ament_add_gmock(test_record_all_no_discovery
ament_add_ros_isolated_gmock(test_record_all_no_discovery
test/rosbag2_transport/test_record_all_no_discovery.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_record_all_no_discovery)
Expand Down
1 change: 1 addition & 0 deletions rosbag2_transport/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>shared_queues_vendor</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>test_msgs</test_depend>
Expand Down

0 comments on commit 84b05a1

Please sign in to comment.