diff --git a/camera_calibration_parsers/CMakeLists.txt b/camera_calibration_parsers/CMakeLists.txt index 487b9f17..a549ccde 100644 --- a/camera_calibration_parsers/CMakeLists.txt +++ b/camera_calibration_parsers/CMakeLists.txt @@ -15,7 +15,6 @@ endif() find_package(ament_cmake_ros REQUIRED) find_package(rclcpp REQUIRED) -find_package(rcpputils REQUIRED) find_package(sensor_msgs REQUIRED) find_package(yaml_cpp_vendor REQUIRED) @@ -32,8 +31,7 @@ target_link_libraries(${PROJECT_NAME} PUBLIC ${sensor_msgs_TARGETS} ${yaml_cpp_vendor_TARGETS}) target_link_libraries(${PROJECT_NAME} PRIVATE - rclcpp::rclcpp - rcpputils::rcpputils) + rclcpp::rclcpp) target_include_directories(${PROJECT_NAME} PUBLIC "$" @@ -86,7 +84,7 @@ install( DESTINATION include/${PROJECT_NAME} ) -ament_export_dependencies(rclcpp rcpputils sensor_msgs yaml_cpp_vendor) +ament_export_dependencies(rclcpp sensor_msgs yaml_cpp_vendor) if(BUILD_TESTING) #TODO(mjcarroll) switch back to this once I can fix copyright check @@ -106,12 +104,12 @@ if(BUILD_TESTING) ament_add_gtest(${PROJECT_NAME}-parse_ini test/test_parse_ini.cpp) if(TARGET ${PROJECT_NAME}-parse_ini) - target_link_libraries(${PROJECT_NAME}-parse_ini ${PROJECT_NAME} rcpputils::rcpputils) + target_link_libraries(${PROJECT_NAME}-parse_ini ${PROJECT_NAME}) endif() ament_add_gtest(${PROJECT_NAME}-parse_yml test/test_parse_yml.cpp) if(TARGET ${PROJECT_NAME}-parse_yml) - target_link_libraries(${PROJECT_NAME}-parse_yml ${PROJECT_NAME} rcpputils::rcpputils) + target_link_libraries(${PROJECT_NAME}-parse_yml ${PROJECT_NAME}) endif() endif() diff --git a/camera_calibration_parsers/package.xml b/camera_calibration_parsers/package.xml index 909386bf..e5f885ef 100644 --- a/camera_calibration_parsers/package.xml +++ b/camera_calibration_parsers/package.xml @@ -21,7 +21,6 @@ sensor_msgs rclcpp - rcpputils yaml_cpp_vendor ament_cmake_gtest diff --git a/camera_calibration_parsers/src/parse.cpp b/camera_calibration_parsers/src/parse.cpp index 97a16838..2b2cc6ee 100644 --- a/camera_calibration_parsers/src/parse.cpp +++ b/camera_calibration_parsers/src/parse.cpp @@ -34,13 +34,13 @@ #include "camera_calibration_parsers/parse.hpp" +#include #include #include "camera_calibration_parsers/parse_ini.hpp" #include "camera_calibration_parsers/parse_yml.hpp" #include "rclcpp/rclcpp.hpp" -#include "rcpputils/filesystem_helper.hpp" namespace camera_calibration_parsers { @@ -49,7 +49,7 @@ bool writeCalibration( const std::string & file_name, const std::string & camera_name, const CameraInfo & cam_info) { - rcpputils::fs::path p(file_name); + std::filesystem::path p(file_name); if (p.extension().string() == ".ini") { return writeCalibrationIni(file_name, camera_name, cam_info); @@ -68,7 +68,7 @@ bool readCalibration( const std::string & file_name, std::string & camera_name, CameraInfo & cam_info) { - rcpputils::fs::path p(file_name); + std::filesystem::path p(file_name); if (p.extension().string() == ".ini") { return readCalibrationIni(file_name, camera_name, cam_info); diff --git a/camera_calibration_parsers/src/parse_ini.cpp b/camera_calibration_parsers/src/parse_ini.cpp index dfc09657..bdd4ca3e 100644 --- a/camera_calibration_parsers/src/parse_ini.cpp +++ b/camera_calibration_parsers/src/parse_ini.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -49,7 +50,6 @@ #include #include "rclcpp/logging.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "sensor_msgs/distortion_models.hpp" namespace camera_calibration_parsers @@ -308,9 +308,9 @@ bool writeCalibrationIni( const std::string & file_name, const std::string & camera_name, const CameraInfo & cam_info) { - rcpputils::fs::path dir(rcpputils::fs::path(file_name).parent_path()); - if (!dir.empty() && !rcpputils::fs::exists(dir) && - !rcpputils::fs::create_directories(dir)) + std::filesystem::path dir(std::filesystem::path(file_name).parent_path()); + if (!dir.empty() && !std::filesystem::exists(dir) && + !std::filesystem::create_directories(dir)) { RCLCPP_ERROR( kIniLogger, "Unable to create directory for camera calibration file [%s]", diff --git a/camera_calibration_parsers/src/parse_yml.cpp b/camera_calibration_parsers/src/parse_yml.cpp index 85192dc8..40264302 100644 --- a/camera_calibration_parsers/src/parse_yml.cpp +++ b/camera_calibration_parsers/src/parse_yml.cpp @@ -38,11 +38,11 @@ #include #include +#include #include #include #include "rclcpp/logging.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "sensor_msgs/distortion_models.hpp" #ifdef _WIN32 @@ -188,9 +188,9 @@ bool writeCalibrationYml( const std::string & file_name, const std::string & camera_name, const CameraInfo & cam_info) { - rcpputils::fs::path dir(rcpputils::fs::path(file_name).parent_path()); - if (!dir.empty() && !rcpputils::fs::exists(dir) && - !rcpputils::fs::create_directories(dir)) + std::filesystem::path dir(std::filesystem::path(file_name).parent_path()); + if (!dir.empty() && !std::filesystem::exists(dir) && + !std::filesystem::create_directories(dir)) { RCLCPP_ERROR( kYmlLogger, "Unable to create directory for camera calibration file [%s]", diff --git a/camera_calibration_parsers/test/test_parse_ini.cpp b/camera_calibration_parsers/test/test_parse_ini.cpp index a05230c8..26e3b28b 100644 --- a/camera_calibration_parsers/test/test_parse_ini.cpp +++ b/camera_calibration_parsers/test/test_parse_ini.cpp @@ -18,7 +18,6 @@ #include #include "camera_calibration_parsers/parse_ini.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "sensor_msgs/distortion_models.hpp" #include "sensor_msgs/msg/camera_info.hpp" diff --git a/camera_calibration_parsers/test/test_parse_yml.cpp b/camera_calibration_parsers/test/test_parse_yml.cpp index 8b659253..904bb579 100644 --- a/camera_calibration_parsers/test/test_parse_yml.cpp +++ b/camera_calibration_parsers/test/test_parse_yml.cpp @@ -19,7 +19,6 @@ #include #include "camera_calibration_parsers/parse_yml.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "sensor_msgs/distortion_models.hpp" #include "sensor_msgs/msg/camera_info.hpp" diff --git a/camera_info_manager/src/camera_info_manager.cpp b/camera_info_manager/src/camera_info_manager.cpp index 9cfd692a..db343435 100644 --- a/camera_info_manager/src/camera_info_manager.cpp +++ b/camera_info_manager/src/camera_info_manager.cpp @@ -38,11 +38,11 @@ #include #include +#include #include #include #include -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/env.hpp" #include "camera_calibration_parsers/parse.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" @@ -508,11 +508,11 @@ CameraInfoManager::saveCalibrationFile( { RCLCPP_INFO(logger_, "writing calibration data to %s", filename.c_str()); - rcpputils::fs::path filepath(filename); - rcpputils::fs::path parent = filepath.parent_path(); + std::filesystem::path filepath(filename); + std::filesystem::path parent = filepath.parent_path(); - if (!rcpputils::fs::exists(parent)) { - if (!rcpputils::fs::create_directories(parent)) { + if (!std::filesystem::exists(parent)) { + if (!std::filesystem::create_directories(parent)) { RCLCPP_ERROR(logger_, "unable to create path directory [%s]", parent.string().c_str()); return false; }