Skip to content

Commit

Permalink
Reapply "Add get_logging_directory method to rclcpp::Logger (#1509)" (#…
Browse files Browse the repository at this point in the history
…1513)

Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno committed Jan 13, 2021
1 parent 8d5af66 commit 56a037a
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 0 deletions.
13 changes: 13 additions & 0 deletions rclcpp/include/rclcpp/logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include "rcl/node.h"
#include "rcutils/logging.h"
#include "rcpputils/filesystem_helper.hpp"

/**
* \def RCLCPP_LOGGING_ENABLED
Expand Down Expand Up @@ -75,6 +76,18 @@ RCLCPP_PUBLIC
Logger
get_node_logger(const rcl_node_t * node);

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

class Logger
{
public:
Expand Down
16 changes: 16 additions & 0 deletions rclcpp/src/rclcpp/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include <string>

#include "rcl_logging_interface/rcl_logging_interface.h"

#include "rclcpp/exceptions.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"
Expand Down Expand Up @@ -46,6 +48,20 @@ get_node_logger(const rcl_node_t * node)
return rclcpp::get_logger(logger_name);
}

rcpputils::fs::path
get_logging_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;
}

void
Logger::set_level(Level level)
{
Expand Down
21 changes: 21 additions & 0 deletions rclcpp/test/rclcpp/test_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#include <memory>
#include <string>

#include "rcutils/env.h"

#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node.hpp"
Expand Down Expand Up @@ -157,3 +159,22 @@ TEST(TestLogger, set_level) {
rcutils_logging_set_output_handler(previous_output_handler);
EXPECT_EQ(RCUTILS_RET_OK, rcutils_logging_shutdown());
}

TEST(TestLogger, get_logging_directory) {
ASSERT_EQ(true, rcutils_set_env("HOME", "/fake_home_dir"));
ASSERT_EQ(true, rcutils_set_env("USERPROFILE", nullptr));
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());
}

0 comments on commit 56a037a

Please sign in to comment.