Skip to content

Commit

Permalink
Updated rcpputils path API (#2579)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jul 24, 2024
1 parent 647bd65 commit b1fdb18
Show file tree
Hide file tree
Showing 8 changed files with 78 additions and 22 deletions.
29 changes: 29 additions & 0 deletions rclcpp/include/rclcpp/logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__LOGGER_HPP_
#define RCLCPP__LOGGER_HPP_

#include <filesystem>
#include <memory>
#include <string>
#include <utility>
Expand Down Expand Up @@ -77,6 +78,14 @@ RCLCPP_PUBLIC
Logger
get_node_logger(const rcl_node_t * node);

// TODO(ahcorde): Remove deprecated class on the next release (in Rolling after Kilted).
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
/// Get the current logging directory.
/**
* For more details of how the logging directory is determined,
Expand All @@ -85,10 +94,30 @@ get_node_logger(const rcl_node_t * node);
* \returns the logging directory being used.
* \throws rclcpp::exceptions::RCLError if an unexpected error occurs.
*/
[[deprecated("use rclcpp::get_log_directory instead of rclcpp::get_logging_directory")]]
RCLCPP_PUBLIC
rcpputils::fs::path
get_logging_directory();

// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

/// Get the current logging directory.
/**
* For more details of how the logging directory is determined,
* see rcl_logging_get_logging_directory().
*
* \returns the logging directory being used.
* \throws rclcpp::exceptions::RCLError if an unexpected error occurs.
*/
RCLCPP_PUBLIC
std::filesystem::path
get_log_directory();

class Logger
{
public:
Expand Down
29 changes: 29 additions & 0 deletions rclcpp/src/rclcpp/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <filesystem>
#include <memory>
#include <string>
#include <utility>
Expand Down Expand Up @@ -54,6 +55,14 @@ get_node_logger(const rcl_node_t * node)
return rclcpp::get_logger(logger_name);
}

// TODO(ahcorde): Remove deprecated class on the next release (in Rolling after Kilted).
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
rcpputils::fs::path
get_logging_directory()
{
Expand All @@ -67,6 +76,26 @@ get_logging_directory()
allocator.deallocate(log_dir, allocator.state);
return path;
}
// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

std::filesystem::path
get_log_directory()
{
char * log_dir = NULL;
auto allocator = rcutils_get_default_allocator();
rcl_logging_ret_t ret = rcl_logging_get_logging_directory(allocator, &log_dir);
if (RCL_LOGGING_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
std::string path{log_dir};
allocator.deallocate(log_dir, allocator.state);
return path;
}

Logger
Logger::get_child(const std::string & suffix)
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <gtest/gtest.h>

#include <algorithm>
#include <filesystem>
#include <memory>
#include <string>
#include <vector>
Expand Down Expand Up @@ -61,7 +62,7 @@ class TestNodeParameters : public ::testing::Test
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeParameters * node_parameters;

rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
};

TEST_F(TestNodeParameters, construct_destruct_rcl_errors) {
Expand Down
15 changes: 4 additions & 11 deletions rclcpp/test/rclcpp/test_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gtest/gtest.h>

#include <filesystem>
#include <memory>
#include <string>

Expand Down Expand Up @@ -210,15 +211,7 @@ TEST(TestLogger, get_logging_directory) {
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", nullptr));
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr));

auto path = rclcpp::get_logging_directory();
auto expected_path = rcpputils::fs::path{"/fake_home_dir"} / ".ros" / "log";

// TODO(ivanpauno): Add operator== to rcpputils::fs::path
auto it = path.cbegin();
auto eit = expected_path.cbegin();
for (; it != path.cend() && eit != expected_path.cend(); ++it, ++eit) {
EXPECT_EQ(*eit, *it);
}
EXPECT_EQ(it, path.cend());
EXPECT_EQ(eit, expected_path.cend());
auto path = rclcpp::get_log_directory();
auto expected_path = std::filesystem::path{"/fake_home_dir"} / ".ros" / "log";
EXPECT_EQ(path, expected_path);
}
3 changes: 2 additions & 1 deletion rclcpp/test/rclcpp/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <gtest/gtest.h>

#include <chrono>
#include <filesystem>
#include <functional>
#include <limits>
#include <map>
Expand Down Expand Up @@ -56,7 +57,7 @@ class TestNode : public ::testing::Test
test_resources_path /= "test_node";
}

rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
};

/*
Expand Down
9 changes: 5 additions & 4 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <gmock/gmock.h>

#include <chrono>
#include <filesystem>
#include <functional>
#include <future>
#include <memory>
Expand Down Expand Up @@ -935,7 +936,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters) {
auto asynchronous_client =
std::make_shared<rclcpp::AsyncParametersClient>(load_node, "/namespace/load_node");
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "load_parameters.yaml").string();
auto load_future = asynchronous_client->load_parameters(parameters_filepath);
Expand All @@ -961,7 +962,7 @@ TEST_F(TestParameterClient, sync_parameter_load_parameters) {
auto synchronous_client =
std::make_shared<rclcpp::SyncParametersClient>(load_node);
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "load_parameters.yaml").string();
auto load_future = synchronous_client->load_parameters(parameters_filepath);
Expand All @@ -983,7 +984,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters_complicated_regex) {
auto asynchronous_client =
std::make_shared<rclcpp::AsyncParametersClient>(load_node, "/namespace/load_node");
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "load_complicated_parameters.yaml").string();
auto load_future = asynchronous_client->load_parameters(parameters_filepath);
Expand Down Expand Up @@ -1013,7 +1014,7 @@ TEST_F(TestParameterClient, async_parameter_load_no_valid_parameter) {
auto asynchronous_client =
std::make_shared<rclcpp::AsyncParametersClient>(load_node, "/namespace/load_node");
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
std::filesystem::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "no_valid_parameters.yaml").string();
EXPECT_THROW(
Expand Down
9 changes: 5 additions & 4 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "rclcpp_components/component_manager.hpp"

#include <filesystem>
#include <functional>
#include <memory>
#include <string>
Expand Down Expand Up @@ -95,11 +96,11 @@ ComponentManager::get_component_resources(
throw ComponentManagerException("Invalid resource entry");
}

std::string library_path = parts[1];
if (!rcpputils::fs::path(library_path).is_absolute()) {
library_path = base_path + "/" + library_path;
std::filesystem::path library_path = parts[1];
if (!library_path.is_absolute()) {
library_path = (base_path / library_path);
}
resources.push_back({parts[0], library_path});
resources.push_back({parts[0], library_path.string()});
}
return resources;
}
Expand Down
3 changes: 2 additions & 1 deletion rclcpp_components/test/test_component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gtest/gtest.h>

#include <filesystem>
#include <memory>

#include "rclcpp_components/component_manager.hpp"
Expand Down Expand Up @@ -51,7 +52,7 @@ TEST_F(TestComponentManager, get_component_resources_valid)
EXPECT_EQ("test_rclcpp_components::TestComponentBar", resources[1].first);
EXPECT_EQ("test_rclcpp_components::TestComponentNoNode", resources[2].first);

namespace fs = rcpputils::fs;
namespace fs = std::filesystem;
EXPECT_TRUE(fs::exists(fs::path(resources[0].second)));
EXPECT_TRUE(fs::exists(fs::path(resources[1].second)));
EXPECT_TRUE(fs::exists(fs::path(resources[2].second)));
Expand Down

0 comments on commit b1fdb18

Please sign in to comment.