diff --git a/rcl/package.xml b/rcl/package.xml index 6d8861dc1..5f6d86c65 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -40,7 +40,6 @@ launch_testing_ament_cmake mimick_vendor osrf_testing_tools_cpp - rcpputils rmw rmw_implementation_cmake rosidl_runtime_cpp diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 27d7dfbeb..22d1aded4 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -3,7 +3,6 @@ find_package(ament_cmake_gtest REQUIRED) find_package(launch_testing_ament_cmake REQUIRED) find_package(mimick_vendor REQUIRED) find_package(osrf_testing_tools_cpp REQUIRED) -find_package(rcpputils REQUIRED) find_package(rcutils REQUIRED) find_package(rmw_implementation_cmake REQUIRED) find_package(rosidl_runtime_cpp REQUIRED) @@ -189,7 +188,6 @@ function(test_target_function) LIBRARIES ${PROJECT_NAME} mimick wait_for_entity_helpers AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp" - "rcpputils" "rcutils" "rosidl_runtime_c" "test_msgs" @@ -394,7 +392,7 @@ rcl_add_custom_gtest(test_arguments APPEND_LIBRARY_DIRS ${extra_lib_dirs} INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools - AMENT_DEPENDENCIES "osrf_testing_tools_cpp" "rcpputils" + AMENT_DEPENDENCIES "osrf_testing_tools_cpp" ) rcl_add_custom_gtest(test_time diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index e77f0bb3d..bb493743a 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -13,12 +13,12 @@ // limitations under the License. #include +#include #include #include #include #include "osrf_testing_tools_cpp/scope_exit.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rcl/rcl.h" #include "rcl/arguments.h" @@ -44,7 +44,7 @@ class TestArgumentsFixture : public ::testing::Test } protected: - rcpputils::fs::path test_path{TEST_RESOURCES_DIRECTORY}; + std::filesystem::path test_path{TEST_RESOURCES_DIRECTORY}; }; #define EXPECT_UNPARSED(parsed_args, ...) \ diff --git a/rcl/test/rcl/test_publisher_wait_all_ack.cpp b/rcl/test/rcl/test_publisher_wait_all_ack.cpp index c931c09aa..6371eb4d0 100644 --- a/rcl/test/rcl/test_publisher_wait_all_ack.cpp +++ b/rcl/test/rcl/test_publisher_wait_all_ack.cpp @@ -14,14 +14,14 @@ #include -#include #include +#include #include +#include #include "rcl/allocator.h" #include "rcl/publisher.h" #include "rcl/subscription.h" -#include "rcpputils/filesystem_helper.hpp" #include "rcutils/env.h" #include "rcl/rcl.h" @@ -58,7 +58,7 @@ class CLASSNAME (TestPublisherFixtureSpecial, RMW_IMPLEMENTATION) : public ::tes // By default, fastdds use intraprocess mode in this scenario. But this leads to high-speed // data transmission. test_wait_for_all_acked need low data transmission. So disable this // mode via fastdds profile file. - rcpputils::fs::path fastdds_profile(TEST_RESOURCES_DIRECTORY); + std::filesystem::path fastdds_profile(TEST_RESOURCES_DIRECTORY); fastdds_profile /= "test_profile/disable_intraprocess.xml"; ASSERT_EQ( rcutils_set_env("FASTRTPS_DEFAULT_PROFILES_FILE", fastdds_profile.string().c_str()), diff --git a/rcl_yaml_param_parser/CMakeLists.txt b/rcl_yaml_param_parser/CMakeLists.txt index a5082ad1e..2315a6432 100644 --- a/rcl_yaml_param_parser/CMakeLists.txt +++ b/rcl_yaml_param_parser/CMakeLists.txt @@ -186,7 +186,6 @@ if(BUILD_TESTING) target_link_libraries(benchmark_parse_yaml ${PROJECT_NAME} performance_test_fixture::performance_test_fixture - rcpputils::rcpputils rcutils::rcutils ) endif() diff --git a/rcl_yaml_param_parser/package.xml b/rcl_yaml_param_parser/package.xml index 8bf1c24c2..0b1d863b1 100644 --- a/rcl_yaml_param_parser/package.xml +++ b/rcl_yaml_param_parser/package.xml @@ -27,7 +27,6 @@ mimick_vendor osrf_testing_tools_cpp performance_test_fixture - rcpputils ament_cmake diff --git a/rcl_yaml_param_parser/test/benchmark/benchmark_parse_yaml.cpp b/rcl_yaml_param_parser/test/benchmark/benchmark_parse_yaml.cpp index 4222b9fd5..377163e2a 100644 --- a/rcl_yaml_param_parser/test/benchmark/benchmark_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/benchmark/benchmark_parse_yaml.cpp @@ -12,14 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include "performance_test_fixture/performance_test_fixture.hpp" #include "rcl_yaml_param_parser/parser.h" -#include "rcpputils/filesystem_helper.hpp" - #include "rcutils/allocator.h" #include "rcutils/error_handling.h" @@ -28,7 +27,7 @@ using performance_test_fixture::PerformanceTest; BENCHMARK_F(PerformanceTest, parser_yaml_param)(benchmark::State & st) { std::string path = - (rcpputils::fs::current_path() / "test" / "benchmark" / "benchmark_params.yaml").string(); + (std::filesystem::current_path() / "test" / "benchmark" / "benchmark_params.yaml").string(); reset_heap_counters(); for (auto _ : st) { RCUTILS_UNUSED(_);