Skip to content

Commit

Permalink
Switch from rcpputils::fs to std::filesystem (#300)
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard authored Feb 27, 2024
1 parent 1a559ed commit feab173
Show file tree
Hide file tree
Showing 8 changed files with 20 additions and 25 deletions.
10 changes: 4 additions & 6 deletions camera_calibration_parsers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand All @@ -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
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
Expand Down Expand Up @@ -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
Expand All @@ -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()

Expand Down
1 change: 0 additions & 1 deletion camera_calibration_parsers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@

<depend>sensor_msgs</depend>
<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>yaml_cpp_vendor</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
6 changes: 3 additions & 3 deletions camera_calibration_parsers/src/parse.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@

#include "camera_calibration_parsers/parse.hpp"

#include <filesystem>
#include <string>

#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
{
Expand All @@ -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);
Expand All @@ -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);
Expand Down
8 changes: 4 additions & 4 deletions camera_calibration_parsers/src/parse_ini.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,14 +42,14 @@

#include <algorithm>
#include <array>
#include <filesystem>
#include <fstream>
#include <limits>
#include <sstream>
#include <string>
#include <vector>

#include "rclcpp/logging.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "sensor_msgs/distortion_models.hpp"

namespace camera_calibration_parsers
Expand Down Expand Up @@ -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]",
Expand Down
8 changes: 4 additions & 4 deletions camera_calibration_parsers/src/parse_yml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@
#include <cstring>
#include <ctime>

#include <filesystem>
#include <fstream>
#include <string>

#include "rclcpp/logging.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "sensor_msgs/distortion_models.hpp"

#ifdef _WIN32
Expand Down Expand Up @@ -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]",
Expand Down
1 change: 0 additions & 1 deletion camera_calibration_parsers/test/test_parse_ini.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <string>

#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"

Expand Down
1 change: 0 additions & 1 deletion camera_calibration_parsers/test/test_parse_yml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <string>

#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"

Expand Down
10 changes: 5 additions & 5 deletions camera_info_manager/src/camera_info_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@

#include <algorithm>
#include <cstdlib>
#include <filesystem>
#include <locale>
#include <memory>
#include <string>

#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/env.hpp"
#include "camera_calibration_parsers/parse.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
Expand Down Expand Up @@ -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;
}
Expand Down

0 comments on commit feab173

Please sign in to comment.