Skip to content

Commit

Permalink
Add set_level for rclcpp::Logger (#1284)
Browse files Browse the repository at this point in the history
* Add set_logger_level for rclcpp::Logger

Signed-off-by: Chen Lihui <Lihui.Chen@sony.com>

* Update based on suggestions

Signed-off-by: Chen Lihui <Lihui.Chen@sony.com>
Co-authored-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>

Co-authored-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
Chen Lihui and fujitatomoya authored Sep 11, 2020
1 parent 0276809 commit 7b2d983
Show file tree
Hide file tree
Showing 3 changed files with 150 additions and 1 deletion.
23 changes: 23 additions & 0 deletions rclcpp/include/rclcpp/logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "rclcpp/visibility_control.hpp"

#include "rcl/node.h"
#include "rcutils/logging.h"

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

class Logger
{
public:
/// An enum for the type of logger level.
enum class Level
{
Unset = RCUTILS_LOG_SEVERITY_UNSET, ///< The unset log level
Debug = RCUTILS_LOG_SEVERITY_DEBUG, ///< The debug log level
Info = RCUTILS_LOG_SEVERITY_INFO, ///< The info log level
Warn = RCUTILS_LOG_SEVERITY_WARN, ///< The warn log level
Error = RCUTILS_LOG_SEVERITY_ERROR, ///< The error log level
Fatal = RCUTILS_LOG_SEVERITY_FATAL, ///< The fatal log level
};

private:
friend Logger rclcpp::get_logger(const std::string & name);
friend ::rclcpp::node_interfaces::NodeLogging;
Expand Down Expand Up @@ -138,6 +151,16 @@ class Logger
}
return Logger(*name_ + "." + suffix);
}

/// Set level for current logger.
/**
* \param[in] level the logger's level
* \throws rclcpp::exceptions::RCLInvalidArgument if level is invalid.
* \throws rclcpp::exceptions::RCLError if other error happens.
*/
RCLCPP_PUBLIC
void
set_level(Level level);
};

} // namespace rclcpp
Expand Down
20 changes: 19 additions & 1 deletion rclcpp/src/rclcpp/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

#include <string>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/logger.hpp"

#include "rclcpp/logging.hpp"

namespace rclcpp
Expand Down Expand Up @@ -44,4 +44,22 @@ get_node_logger(const rcl_node_t * node)
return rclcpp::get_logger(logger_name);
}

void
Logger::set_level(Level level)
{
rcutils_ret_t rcutils_ret = rcutils_logging_set_logger_level(
get_name(),
static_cast<RCUTILS_LOG_SEVERITY>(level));
if (rcutils_ret != RCUTILS_RET_OK) {
if (rcutils_ret == RCUTILS_RET_INVALID_ARGUMENT) {
exceptions::throw_from_rcl_error(
RCL_RET_INVALID_ARGUMENT, "Invalid parameter",
rcutils_get_error_state(), rcutils_reset_error);
}
exceptions::throw_from_rcl_error(
RCL_RET_ERROR, "Couldn't set logger level",
rcutils_get_error_state(), rcutils_reset_error);
}
}

} // namespace rclcpp
108 changes: 108 additions & 0 deletions rclcpp/test/rclcpp/test_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,114 @@ TEST(TestLogger, get_node_logger) {
EXPECT_STREQ(logger.get_name(), "ns.my_node");

logger = rclcpp::get_node_logger(nullptr);
rcl_reset_error();
EXPECT_STREQ(logger.get_name(), "rclcpp");
rclcpp::shutdown();
}

struct LogEvent
{
bool console_output_handler_called;
std::string message;
};
LogEvent g_last_log_event;

TEST(TestLogger, set_level) {
ASSERT_EQ(RCUTILS_RET_OK, rcutils_logging_initialize());

rclcpp::Logger logger = rclcpp::get_logger("test_logger");
EXPECT_THROW(
{
logger.set_level(static_cast<rclcpp::Logger::Level>(99999));
}, rclcpp::exceptions::RCLInvalidArgument);

auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t *,
int, const char *, rcutils_time_point_value_t,
const char * format, va_list * args) -> void
{
g_last_log_event.console_output_handler_called = true;
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), format, *args);
g_last_log_event.message = buffer;
};

rcutils_logging_output_handler_t previous_output_handler = rcutils_logging_get_output_handler();
rcutils_logging_set_output_handler(rcutils_logging_console_output_handler);

// default
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// unset
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Unset);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// debug
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Debug);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message debug", g_last_log_event.message);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_EQ("message info", g_last_log_event.message);

// info
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Info);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// warn
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Warn);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message warn", g_last_log_event.message);

// error
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Error);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_ERROR(logger, std::string("message %s"), "error");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message error", g_last_log_event.message);

// fatal
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Fatal);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_ERROR(logger, std::string("message %s"), "error");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_FATAL(logger, std::string("message %s"), "fatal");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message fatal", g_last_log_event.message);

rcutils_logging_set_output_handler(previous_output_handler);
EXPECT_EQ(RCUTILS_RET_OK, rcutils_logging_shutdown());
}

0 comments on commit 7b2d983

Please sign in to comment.